From 1609e61c69c8f1258f88822da38e887b5b54939f Mon Sep 17 00:00:00 2001 From: fherrero <fherrero@iri.upc.edu> Date: Tue, 27 Jun 2017 10:02:43 +0200 Subject: [PATCH] twist_to_manual_control: launch topics as arguments --- cfg/TwistToManualControl.cfg | 3 -- launch/node.launch | 53 ++++++++++++++++++------------------ 2 files changed, 26 insertions(+), 30 deletions(-) diff --git a/cfg/TwistToManualControl.cfg b/cfg/TwistToManualControl.cfg index 50e2aba..5653eda 100755 --- a/cfg/TwistToManualControl.cfg +++ b/cfg/TwistToManualControl.cfg @@ -54,7 +54,4 @@ gen.add("linear_sat_max", double_t, 0, "Minimum input linear speed ", 0.5, -5.0 gen.add("invert_speed", bool_t, 0, "Invert speed signum", False) gen.add("invert_steering", bool_t, 0, "Invert steering direction", False) - - - exit(gen.generate(PACKAGE, "TwistToManualControlAlgorithm", "TwistToManualControl")) diff --git a/launch/node.launch b/launch/node.launch index 4c779e6..ba8fdd4 100644 --- a/launch/node.launch +++ b/launch/node.launch @@ -4,35 +4,34 @@ <arg name="node_name" default="twist_to_manual_control"/> <arg name="invert_speed" default="True"/> <arg name="invert_steering" default="True"/> + <arg name="twist_topic" default="/cmd_vel"/> + <arg name="steering_topic" default="/manual_control/steering"/> + <arg name="speed_topic" default="/manual_control/speed"/> -<!-- <group ns="$(optenv ROBOT car)">--> - - <node pkg ="twist_to_manual_control" - type="twist_to_manual_control" - name="$(arg node_name)" - output="screen"> - <remap from="~cmd_vel" to="/cmd_vel"/> - <remap from="~steering" to="/manual_control/steering"/> - <remap from="~speed" to="/manual_control/speed"/> - - <param name="steering_min" value="20"/> - <param name="steering_zero" value="90"/> - <param name="steering_max" value="160"/> - - <param name="angular_sat_min" value="-1.0"/> - <param name="angular_sat_max" value="1.0"/> - - <param name="speed_min" value="-1000"/> - <param name="speed_zero" value="0"/> - <param name="speed_max" value="1000"/> - - <param name="linear_sat_min" value="-1.0"/> - <param name="linear_sat_max" value="1.0"/> + <node pkg ="twist_to_manual_control" + type="twist_to_manual_control" + name="$(arg node_name)" + output="screen"> + <remap from="~cmd_vel" to="$(arg twist_topic)"/> + <remap from="~steering" to="$(arg steering_topic)"/> + <remap from="~speed" to="$(arg speed_topic)"/> - <param name="invert_speed" value="$(arg invert_speed)"/> - <param name="invert_steering" value="$(arg invert_steering)"/> - </node> + <param name="steering_min" value="30"/> + <param name="steering_zero" value="90"/> + <param name="steering_max" value="150"/> -<!-- </group>--> + <param name="angular_sat_min" value="-1.0"/> + <param name="angular_sat_max" value="1.0"/> + + <param name="speed_min" value="-1000"/> + <param name="speed_zero" value="0"/> + <param name="speed_max" value="1000"/> + + <param name="linear_sat_min" value="-1.0"/> + <param name="linear_sat_max" value="1.0"/> + + <param name="invert_speed" value="$(arg invert_speed)"/> + <param name="invert_steering" value="$(arg invert_steering)"/> + </node> </launch> -- GitLab