diff --git a/launch/play_motion_client.launch b/launch/play_motion_client.launch new file mode 100644 index 0000000000000000000000000000000000000000..977318fd21b2673202681d497797618b08401e1e --- /dev/null +++ b/launch/play_motion_client.launch @@ -0,0 +1,20 @@ +<launch> + + <!-- launch the play motion client node --> + <node name="play_motion_client" + pkg="play_motion_client" + type="play_motion_client" + output="screen" + ns="/tiago"> + <remap from="~/play_motion_module/play_motion" + to="/play_motion"/> + + <rosparam file="$(find tiago_modules)/config/play_motion_module_default.yaml" command="load" ns="play_motion_module" /> + </node> + + <!-- launch dynamic reconfigure --> + <node name="rqt_reconfigure" pkg="rqt_reconfigure" type="rqt_reconfigure" respawn="false" + output="screen"/> + +</launch> + diff --git a/launch/play_motion_client_sim.launch b/launch/play_motion_client_sim.launch index ba7f47c583948d32216090e0c3f3d8f78f69398b..0e65dd190ecc8ad908ab44c2312941e2a1882879 100644 --- a/launch/play_motion_client_sim.launch +++ b/launch/play_motion_client_sim.launch @@ -5,25 +5,7 @@ <arg name="robot" value="steel" /> </include> - <!-- launch the play motion client node --> - <node name="play_motion_client" - pkg="play_motion_client" - type="play_motion_client" - output="screen" - ns="/tiago"> - <remap from="~/play_motion_module/play_motion" - to="/play_motion"/> - <param name="~/play_motion_module/action_max_retries" value="5"/> - <param name="~/play_motion_module/enable_timeout" value="false"/> - <param name="~/play_motion_module/feedback_watchdog_time_s" value="20"/> - <param name="~/play_motion_module/rate_hz" value="10"/> - <param name="~/play_motion_module/timeout_s" value="10"/> - <param name="~/play_motion_module/enabled" value="true"/> - </node> - - <!-- launch dynamic reconfigure --> - <node name="rqt_reconfigure" pkg="rqt_reconfigure" type="rqt_reconfigure" respawn="false" - output="screen"/> + <include file="$(find play_motion_client)/launch/play_motion_client.launch"> </launch> diff --git a/src/play_motion_client_alg_node.cpp b/src/play_motion_client_alg_node.cpp index 766125f197ce37a8e42744754f5cd77bbd579271..4bea89924e1e9a71bd8254bccfccfc524a694e72 100644 --- a/src/play_motion_client_alg_node.cpp +++ b/src/play_motion_client_alg_node.cpp @@ -3,7 +3,7 @@ PlayMotionClientAlgNode::PlayMotionClientAlgNode(void) : algorithm_base::IriBaseAlgorithm<PlayMotionClientAlgorithm>(), - play_motion("play_motion_module") + play_motion("play_motion_module",ros::this_node::getName()) { //init class attributes if necessary //this->loop_rate_ = 2;//in [Hz]