Skip to content
Snippets Groups Projects
Commit 960affb6 authored by Fernando Herrero's avatar Fernando Herrero
Browse files

Remapped speed to manual_control/speed

parent 849d8915
No related branches found
No related tags found
No related merge requests found
......@@ -6,7 +6,7 @@
<arg name="invert_steering" default="True"/>
<arg name="twist_topic" default="/cmd_vel"/>
<arg name="steering_topic" default="/steering"/>
<arg name="speed_topic" default="/speed"/>
<arg name="speed_topic" default="/manual_control/speed"/>
<node pkg ="iri_twist_to_manual_control"
type="iri_twist_to_manual_control"
......
......@@ -2,7 +2,7 @@
<launch>
<arg name="name" default="teleop_keyboard"/>
<arg name="speed_topic" default="/speed"/>
<arg name="speed_topic" default="/manual_control/speed"/>
<arg name="steering_topic" default="/steering"/>
<node pkg ="teleop_twist_keyboard"
......@@ -10,13 +10,17 @@
type="teleop_twist_keyboard.py"
output="screen">
<remap from="cmd_vel" to="$(arg name)/cmd_vel"/>
<!--
<param name="~speed" value="0.25"/>
<param name="~turn" value="0.5"/>
-->
</node>
<include file="$(find iri_twist_to_manual_control)/launch/node.launch">
<arg name="node_name" value="$(arg name)_twist_to_manual_control"/>
<arg name="invert_speed" value="False"/>
<arg name="invert_steering" value="True"/>
<arg name="twist_topic" default="$(arg name)/cmd_vel"/>
<arg name="twist_topic" value="$(arg name)/cmd_vel"/>
<arg name="steering_topic" value="$(arg steering_topic)"/>
<arg name="speed_topic" value="$(arg speed_topic)"/>
</include>
......
......@@ -4,7 +4,7 @@
<arg name="name" default="teleop_ps3"/>
<arg name="dev" default="/dev/input/ps3joy"/>
<arg name="config_filepath" default="$(find twist_to_manual_control)/config/ps3.yaml" />
<arg name="speed_topic" default="/speed"/>
<arg name="speed_topic" default="/manual_control/speed"/>
<arg name="steering_topic" default="/steering"/>
<node pkg="joy" type="joy_node" name="joy_node">
......@@ -22,7 +22,7 @@
<arg name="node_name" value="$(arg name)_twist_to_manual_control"/>
<arg name="invert_speed" value="False"/>
<arg name="invert_steering" value="True"/>
<arg name="twist_topic" default="$(arg name)/cmd_vel"/>
<arg name="twist_topic" value="$(arg name)/cmd_vel"/>
<arg name="steering_topic" value="$(arg steering_topic)"/>
<arg name="speed_topic" value="$(arg speed_topic)"/>
</include>
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment