|
From: <is...@us...> - 2009-07-06 22:41:18
|
Revision: 18352
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=18352&view=rev
Author: isucan
Date: 2009-07-06 22:41:13 +0000 (Mon, 06 Jul 2009)
Log Message:
-----------
update frame names
Modified Paths:
--------------
pkg/trunk/highlevel/move_arm/src/arm_cmd_line.cpp
pkg/trunk/motion_planning/planning_environment/src/kinematic_model_state_monitor.cpp
Modified: pkg/trunk/highlevel/move_arm/src/arm_cmd_line.cpp
===================================================================
--- pkg/trunk/highlevel/move_arm/src/arm_cmd_line.cpp 2009-07-06 22:38:51 UTC (rev 18351)
+++ pkg/trunk/highlevel/move_arm/src/arm_cmd_line.cpp 2009-07-06 22:41:13 UTC (rev 18352)
@@ -96,7 +96,7 @@
for (unsigned int i = 0 ; i < goal.goal_constraints.joint_constraint.size(); ++i)
{
goal.goal_constraints.joint_constraint[i].header.stamp = ros::Time::now();
- goal.goal_constraints.joint_constraint[i].header.frame_id = "base_link";
+ goal.goal_constraints.joint_constraint[i].header.frame_id = "/base_link";
goal.goal_constraints.joint_constraint[i].joint_name = names[i];
goal.goal_constraints.joint_constraint[i].value.resize(1);
goal.goal_constraints.joint_constraint[i].toleranceAbove.resize(1);
@@ -113,7 +113,7 @@
goal.goal_constraints.pose_constraint[0].type = motion_planning_msgs::PoseConstraint::POSITION_XYZ + motion_planning_msgs::PoseConstraint::ORIENTATION_RPY;
goal.goal_constraints.pose_constraint[0].link_name = link;
goal.goal_constraints.pose_constraint[0].pose.header.stamp = ros::Time::now();
- goal.goal_constraints.pose_constraint[0].pose.header.frame_id = "base_link";
+ goal.goal_constraints.pose_constraint[0].pose.header.frame_id = "/base_link";
goal.goal_constraints.pose_constraint[0].pose.pose.position.x = x;
goal.goal_constraints.pose_constraint[0].pose.pose.position.y = y;
goal.goal_constraints.pose_constraint[0].pose.pose.position.z = z;
Modified: pkg/trunk/motion_planning/planning_environment/src/kinematic_model_state_monitor.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/kinematic_model_state_monitor.cpp 2009-07-06 22:38:51 UTC (rev 18351)
+++ pkg/trunk/motion_planning/planning_environment/src/kinematic_model_state_monitor.cpp 2009-07-06 22:41:13 UTC (rev 18352)
@@ -64,7 +64,7 @@
if (dynamic_cast<planning_models::KinematicModel::FloatingJoint*>(kmodel_->getRobot(0)->chain))
floatingJoint_ = kmodel_->getRobot(0)->chain->name;
- robot_frame_ = kmodel_->getRobot(0)->chain->after->name;
+ robot_frame_ = "/" + kmodel_->getRobot(0)->chain->after->name;
ROS_DEBUG("Robot frame is '%s'", robot_frame_.c_str());
if (includePose_)
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|