Skip to content
Snippets Groups Projects
Commit 95a40135 authored by Nikhil Ambardar's avatar Nikhil Ambardar
Browse files

Update robot_models_node.cpp

parent 5543ea9b
Branches
No related tags found
No related merge requests found
......@@ -55,13 +55,13 @@
worldobject o10;
o5a.name = "panda_joint1";
o5b.name = "panda_joint2";
o5c.name = "panda_joint3";
o5d.name = "panda_joint4";
o5e.name = "panda_joint5";
o5f.name = "panda_joint6";
o5g.name = "panda_joint7";
//o5a.name = "panda_joint1";
//o5b.name = "panda_joint2";
//o5c.name = "panda_joint3";
//o5d.name = "panda_joint4";
//o5e.name = "panda_joint5";
//o5f.name = "panda_joint6";
//o5g.name = "panda_joint7";
o5a.x = 1.7;
o5b.y = 1.8;
o5c.z = 1.9;
......@@ -107,13 +107,13 @@
{
geometry_msgs::TransformStamped transformStamped;
try {
transformStamped = tfBuffer.lookupTransform("panda_joint1", tfBuffer.o5a, ros::Time(0));
transformStamped = tfBuffer.lookupTransform("panda_joint2", tfBuffer.o5b, ros::Time(0));
transformStamped = tfBuffer.lookupTransform("panda_joint3", o5c, ros::Time(0));
transformStamped = tfBuffer.lookupTransform("panda_joint4", o5d, ros::Time(0));
transformStamped = tfBuffer.lookupTransform("panda_joint5", o5e, ros::Time(0));
transformStamped = tfBuffer.lookupTransform("panda_joint6", o5f, ros::Time(0));
transformStamped = tfBuffer.lookupTransform("panda_joint7", To5g, ros::Time(0));
transformStamped = tfBuffer.lookupTransform("panda_joint1", o5a.name, ros::Time(0));
transformStamped = tfBuffer.lookupTransform("panda_joint2", o5b.name, ros::Time(0));
transformStamped = tfBuffer.lookupTransform("panda_joint3", o5c.name, ros::Time(0));
transformStamped = tfBuffer.lookupTransform("panda_joint4", o5d.name, ros::Time(0));
transformStamped = tfBuffer.lookupTransform("panda_joint5", o5e.name, ros::Time(0));
transformStamped = tfBuffer.lookupTransform("panda_joint6", o5f.name, ros::Time(0));
transformStamped = tfBuffer.lookupTransform("panda_joint7", o5g.name, ros::Time(0));
} catch (tf2::TransformException &ex) {
ROS_WARN("%s", ex.what());
ros::Duration(0.1).sleep();
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment