Skip to content

Commit f39fc58

Browse files
committed
Remove initial slash from TF frame name
1 parent 191a88c commit f39fc58

File tree

3 files changed

+8
-8
lines changed

3 files changed

+8
-8
lines changed

doc/bullet_collision_checker/src/bullet_collision_checker_tutorial.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -256,7 +256,7 @@ int main(int argc, char** argv)
256256
marker_publisher.publish(marker_delete);
257257

258258
visualization_msgs::Marker marker;
259-
marker.header.frame_id = "/panda_link0";
259+
marker.header.frame_id = "panda_link0";
260260
marker.header.stamp = ros::Time::now();
261261
marker.ns = "world_cube";
262262
marker.id = 0;

doc/interactivity/include/interactivity/imarker.h

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -65,7 +65,7 @@ class IMarker
6565

6666
/** create an interactive marker at the origin */
6767
IMarker(interactive_markers::InteractiveMarkerServer& server, const std::string& name,
68-
const std::string& frame_id = "/panda_link0",
68+
const std::string& frame_id = "panda_link0",
6969
boost::function<void(const visualization_msgs::InteractiveMarkerFeedbackConstPtr&)> callback = printFeedback,
7070
Dof dof = BOTH)
7171
: imarker_()
@@ -76,7 +76,7 @@ class IMarker
7676

7777
/** create an interactive marker with an initial pose */
7878
IMarker(interactive_markers::InteractiveMarkerServer& server, const std::string& name, const Eigen::Isometry3d& pose,
79-
const std::string& frame_id = "/panda_link0",
79+
const std::string& frame_id = "panda_link0",
8080
boost::function<void(const visualization_msgs::InteractiveMarkerFeedbackConstPtr&)> callback = printFeedback,
8181
Dof dof = BOTH)
8282
: imarker_()
@@ -90,7 +90,7 @@ class IMarker
9090
/** create an interactive marker with an initial pose */
9191
IMarker(interactive_markers::InteractiveMarkerServer& server, const std::string& name,
9292
const Eigen::Vector3d& position, const Eigen::Quaterniond& orientation,
93-
const std::string& frame_id = "/panda_link0",
93+
const std::string& frame_id = "panda_link0",
9494
boost::function<void(const visualization_msgs::InteractiveMarkerFeedbackConstPtr&)> callback = printFeedback,
9595
Dof dof = BOTH)
9696
: imarker_()
@@ -100,7 +100,7 @@ class IMarker
100100

101101
/** create an interactive marker with an initial position */
102102
IMarker(interactive_markers::InteractiveMarkerServer& server, const std::string& name,
103-
const Eigen::Vector3d& position, const std::string& frame_id = "/panda_link0",
103+
const Eigen::Vector3d& position, const std::string& frame_id = "panda_link0",
104104
boost::function<void(const visualization_msgs::InteractiveMarkerFeedbackConstPtr&)> callback = printFeedback,
105105
Dof dof = BOTH)
106106
: imarker_()

doc/interactivity/src/interactive_robot.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -88,12 +88,12 @@ InteractiveRobot::InteractiveRobot(const std::string& robot_description, const s
8888
desired_group_end_link_pose_ = robot_state_->getGlobalLinkTransform(end_link);
8989

9090
// Create a marker to control the "panda_arm" group
91-
imarker_robot_ = new IMarker(interactive_marker_server_, "robot", desired_group_end_link_pose_, "/panda_link0",
91+
imarker_robot_ = new IMarker(interactive_marker_server_, "robot", desired_group_end_link_pose_, "panda_link0",
9292
boost::bind(movedRobotMarkerCallback, this, boost::placeholders::_1), IMarker::BOTH);
9393

9494
// create an interactive marker to control the world geometry (the yellow cube)
9595
desired_world_object_pose_ = DEFAULT_WORLD_OBJECT_POSE_;
96-
imarker_world_ = new IMarker(interactive_marker_server_, "world", desired_world_object_pose_, "/panda_link0",
96+
imarker_world_ = new IMarker(interactive_marker_server_, "world", desired_world_object_pose_, "panda_link0",
9797
boost::bind(movedWorldMarkerCallback, this, boost::placeholders::_1), IMarker::POS);
9898

9999
// start publishing timer.
@@ -287,7 +287,7 @@ void InteractiveRobot::setWorldObjectPose(const Eigen::Isometry3d& pose)
287287
void InteractiveRobot::publishWorldState()
288288
{
289289
visualization_msgs::Marker marker;
290-
marker.header.frame_id = "/panda_link0";
290+
marker.header.frame_id = "panda_link0";
291291
marker.header.stamp = ros::Time::now();
292292
marker.ns = "world_box";
293293
marker.id = 0;

0 commit comments

Comments
 (0)