Skip to content

Commit 9ad1fec

Browse files
authored
Merge PR #778: fix several issues since panda_moveit_config 0.8
* Load panda_moveit_config/kinematics.yaml with substitution of args * Remove initial slash from TF frame name * Improve output formatting * Load panda.srdf.xacro with hand:=true (consistently to .urdf) * Initialize robot pose to "ready" pose
2 parents 27672e5 + 16ad139 commit 9ad1fec

File tree

12 files changed

+36
-24
lines changed

12 files changed

+36
-24
lines changed
Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,23 +1,24 @@
11
<launch>
2+
<arg name="arm_id" default="panda"/>
23

34
<!-- load URDF -->
45
<param name="robot_description"
56
command="$(find xacro)/xacro '$(find franka_description)/robots/panda/panda.urdf.xacro hand:=true'"/>
67

78
<!-- load SRDF -->
8-
<param name="robot_description_semantic" command="$(find xacro)/xacro '$(find panda_moveit_config)/config/panda.srdf.xacro'"/>
9+
<param name="robot_description_semantic" command="$(find xacro)/xacro '$(find panda_moveit_config)/config/panda.srdf.xacro' hand:=true"/>
910

1011
<!-- Run RViz with a custom config -->
1112
<node name="$(anon rviz)" pkg="rviz" type="rviz" respawn="false" args="-d $(find moveit_tutorials)/doc/bullet_collision_checker/launch/moveit.rviz" output="screen">
12-
<rosparam command="load" file="$(find panda_moveit_config)/config/kinematics.yaml"/>
13+
<rosparam command="load" file="$(find panda_moveit_config)/config/kinematics.yaml" subst_value="true"/>
1314
</node>
1415

1516
<!-- If needed, broadcast static tf2 for robot root -->
1617
<node pkg="tf2_ros" type="static_transform_publisher" name="virtual_joint_broadcaster_0" args="0 0 0 0 0 1 /world/panda_link0 /panda_link0 10" />
1718

1819
<!-- launch interactivity_tutorial -->
1920
<node name="bullet_collision_tutorial" pkg="moveit_tutorials" type="bullet_collision_checker_tutorial" respawn="false" output="screen">
20-
<rosparam command="load" file="$(find panda_moveit_config)/config/kinematics.yaml"/>
21+
<rosparam command="load" file="$(find panda_moveit_config)/config/kinematics.yaml" subst_value="true"/>
2122
</node>
2223

2324
</launch>

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_()
Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,5 @@
11
<launch>
2+
<arg name="arm_id" default="panda"/>
23

34
<!-- load URDF -->
45
<param name="robot_description" command="$(find xacro)/xacro '$(find panda_description)/robots/panda.urdf.xacro'" />
@@ -8,12 +9,12 @@
89

910
<!-- launch rviz -->
1011
<node name="$(anon rviz)" pkg="rviz" type="rviz" respawn="false" output="screen">
11-
<rosparam command="load" file="$(find panda_moveit_config)/config/kinematics.yaml"/>
12+
<rosparam command="load" file="$(find panda_moveit_config)/config/kinematics.yaml" subst_value="true"/>
1213
</node>
1314

1415
<!-- launch interactivity_tutorial -->
1516
<node name="attached_body_tutorial" pkg="moveit_tutorials" type="attached_body_tutorial" respawn="false" output="screen">
16-
<rosparam command="load" file="$(find panda_moveit_config)/config/kinematics.yaml"/>
17+
<rosparam command="load" file="$(find panda_moveit_config)/config/kinematics.yaml" subst_value="true"/>
1718
</node>
1819

1920
</launch>
Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,5 @@
11
<launch>
2+
<arg name="arm_id" default="panda"/>
23

34
<!-- load URDF -->
45
<param name="robot_description" command="$(find xacro)/xacro '$(find panda_description)/robots/panda.urdf.xacro'" />
@@ -8,12 +9,12 @@
89

910
<!-- launch rviz -->
1011
<node name="$(anon rviz)" pkg="rviz" type="rviz" respawn="false" output="screen">
11-
<rosparam command="load" file="$(find panda_moveit_config)/config/kinematics.yaml"/>
12+
<rosparam command="load" file="$(find panda_moveit_config)/config/kinematics.yaml" subst_value="true"/>
1213
</node>
1314

1415
<!-- launch interactivity_tutorial -->
1516
<node name="interactivity_tutorial" pkg="moveit_tutorials" type="interactivity_tutorial" respawn="false" output="screen">
16-
<rosparam command="load" file="$(find panda_moveit_config)/config/kinematics.yaml"/>
17+
<rosparam command="load" file="$(find panda_moveit_config)/config/kinematics.yaml" subst_value="true"/>
1718
</node>
1819

1920
</launch>

doc/interactivity/src/interactive_robot.cpp

Lines changed: 6 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -80,20 +80,22 @@ InteractiveRobot::InteractiveRobot(const std::string& robot_description, const s
8080
ROS_ERROR("Could not get RobotState from Model");
8181
throw RobotLoadException();
8282
}
83-
robot_state_->setToDefaultValues();
8483

8584
// Prepare to move the "panda_arm" group
8685
group_ = robot_state_->getJointModelGroup("panda_arm");
86+
// Initialize pose to "ready"
87+
robot_state_->setToDefaultValues(group_, "ready");
88+
8789
std::string end_link = group_->getLinkModelNames().back();
8890
desired_group_end_link_pose_ = robot_state_->getGlobalLinkTransform(end_link);
8991

9092
// 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",
93+
imarker_robot_ = new IMarker(interactive_marker_server_, "robot", desired_group_end_link_pose_, "panda_link0",
9294
boost::bind(movedRobotMarkerCallback, this, boost::placeholders::_1), IMarker::BOTH);
9395

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

99101
// start publishing timer.
@@ -287,7 +289,7 @@ void InteractiveRobot::setWorldObjectPose(const Eigen::Isometry3d& pose)
287289
void InteractiveRobot::publishWorldState()
288290
{
289291
visualization_msgs::Marker marker;
290-
marker.header.frame_id = "/panda_link0";
292+
marker.header.frame_id = "panda_link0";
291293
marker.header.stamp = ros::Time::now();
292294
marker.ns = "world_box";
293295
marker.id = 0;

doc/motion_planning_api/launch/motion_planning_api_tutorial.launch

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,8 @@
11
<launch>
2+
<arg name="arm_id" default="panda"/>
23

34
<node name="motion_planning_api_tutorial" pkg="moveit_tutorials" type="motion_planning_api_tutorial" respawn="false" output="screen">
4-
<rosparam command="load" file="$(find panda_moveit_config)/config/kinematics.yaml"/>
5+
<rosparam command="load" file="$(find panda_moveit_config)/config/kinematics.yaml" subst_value="true"/>
56
<param name="/planning_plugin" value="ompl_interface/OMPLPlanner"/>
67
<rosparam command="load" file="$(find panda_moveit_config)/config/ompl_planning.yaml"/>
78
</node>

doc/moveit_cpp/launch/moveit_cpp_tutorial.launch

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,5 @@
11
<launch>
2+
<arg name="arm_id" default="panda"/>
23

34
<!-- Specify the config files to use -->
45
<rosparam ns="moveit_cpp_tutorial" command="load" file="$(find moveit_tutorials)/doc/moveit_cpp/config/moveit_cpp.yaml" />
@@ -30,7 +31,7 @@
3031
<!-- Launch RViz -->
3132
<node name="$(anon rviz)" pkg="rviz" type="rviz" respawn="false"
3233
args="-d $(find moveit_tutorials)/doc/moveit_cpp/launch/moveit_cpp_tutorial.rviz" output="screen">
33-
<rosparam command="load" file="$(find panda_moveit_config)/config/kinematics.yaml"/>
34+
<rosparam command="load" file="$(find panda_moveit_config)/config/kinematics.yaml" subst_value="true"/>
3435
</node>
3536

3637
<include file="$(find moveit_tutorials)/doc/moveit_cpp/launch/moveit_cpp_node.launch"/>
Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,11 +1,13 @@
11
<launch>
2+
<arg name="arm_id" default="panda"/>
3+
24
<!-- send Panda urdf to parameter server -->
35
<param name="robot_description"
46
command="$(find xacro)/xacro '$(find franka_description)/robots/panda/panda.urdf.xacro' hand:=true"/>
57

68
<include file="$(find panda_moveit_config)/launch/planning_context.launch"/>
79

810
<node name="planning_scene_tutorial" pkg="moveit_tutorials" type="planning_scene_tutorial" respawn="false" output="screen">
9-
<rosparam command="load" file="$(find panda_moveit_config)/config/kinematics.yaml"/>
11+
<rosparam command="load" file="$(find panda_moveit_config)/config/kinematics.yaml" subst_value="true"/>
1012
</node>
1113
</launch>
Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,9 +1,11 @@
11
<launch>
2+
<arg name="arm_id" default="panda"/>
3+
24
<include file="$(find panda_moveit_config)/launch/planning_context.launch">
35
<arg name="load_robot_description" value="true"/>
46
</include>
57

68
<node name="state_display_tutorial" pkg="moveit_tutorials" type="state_display_tutorial" respawn="false" output="screen">
7-
<rosparam command="load" file="$(find panda_moveit_config)/config/kinematics.yaml"/>
9+
<rosparam command="load" file="$(find panda_moveit_config)/config/kinematics.yaml" subst_value="true"/>
810
</node>
911
</launch>

0 commit comments

Comments
 (0)