[ROS Q&A] 139 – [Solved] Pioneer p3dx simulation on Gazebo, not stopping on key release

Written by Marco Arruda

14/07/2018

In this video we are going to show how to solve the problem of a pioneer 3dx gazebo robot that still moves even after releasing the keyboard, using keyboard twist teleop.

Original question: https://answers.ros.org/question/296803/pioneer_p3dx-simulation-on-gazebo-not-stopping-on-key-release/


Related recourses:

Step 1. Create a project in ROS Development Studio(ROSDS)

ROSDS helps you follow our tutorial in a fast pace without dealing without setting up an environment locally. If you haven’t had an account yet, you can create a free account here. Let’s create a new project and call it pioneer3dx_do_not_stop.

Step 2. Clone the repository

To reproduce the problem, we have to clone it from the original repository. Create a folder called p3dx under the simulation_ws/src and run the following commands to clone the repository.

cd simulation_ws/src/
mkdir p3dx && cd p3dx
git clone https://github.com/RafBerkvens/ua_ros_p3dx.git

Then you can run the simulation from Simulations->select launch file->gazebo.launch

You can try to control the robot by sending the command to the /p3dx/cmd_vel topic. Then you’ll see the problem. The robot won’t stop even when we stop sending command.

To fix this, we comment out these lines in the /p3dx/p3dx_description/urdf/pioneer3dx.gazebo file

  <!--
	<gazebo>
		<plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so">
			<alwaysOn>true</alwaysOn>
			<updateRate>100</updateRate>
			<leftJoint>base_right_wheel_joint</leftJoint>
			<rightJoint>base_left_wheel_joint</rightJoint>
			<wheelSeparation>0.39</wheelSeparation>
			<wheelDiameter>0.15</wheelDiameter>
			<torque>5</torque>
			<commandTopic>${ns}/cmd_vel</commandTopic>
			<odometryTopic>${ns}/odom</odometryTopic>
			<odometryFrame>odom</odometryFrame>
			<robotBaseFrame>base_link</robotBaseFrame>
		</plugin>
	</gazebo>
-->

We want to change the controller which support timeout control and we also have to specify transmission property. Several parts have been changed in the repository. You can find the changes in detail here. We also need a parameter file for the controller. Create a file called control.yaml under the /p3dx/p3dx_control/ directory with the following content.

p3dx_joint_publisher:
  type: "joint_state_controller/JointStateController"
  publish_rate: 50

p3dx_velocity_controller:
  type: "diff_drive_controller/DiffDriveController"
  left_wheel: 'base_right_wheel_joint'
  right_wheel: 'base_left_wheel_joint'
  publish_rate: 50
  pose_covariance_diagonal: [0.001, 0.001, 0.001, 0.001, 0.001, 0.03]
  twist_covariance_diagonal: [0.001, 0.001, 0.001, 0.001, 0.001, 0.03]
  cmd_vel_timeout: 0.25
  wheel_separation : 0.39
  wheel_radius : 0.15

We also have to modify the gazeno.launch file like this to launch the controller.

<launch>

	<!-- these are the arguments you can pass this launch file, for example 
		paused:=true -->
	<arg name="paused" default="false" />
	<arg name="use_sim_time" default="true" />
	<arg name="gui" default="true" />
	<arg name="headless" default="false" />
	<arg name="debug" default="false" />

	<!-- We resume the logic in empty_world.launch, changing only the name of 
		the world to be launched -->
	<include file="$(find gazebo_ros)/launch/empty_world.launch">
		<!--<arg name="world_name" value="$(find p3dx_gazebo)/worlds/p3dx.world" />-->
		<arg name="debug" value="$(arg debug)" />
		<arg name="gui" value="$(arg gui)" />
		<arg name="paused" value="$(arg paused)" />
		<arg name="use_sim_time" value="$(arg use_sim_time)" />
		<arg name="headless" value="$(arg headless)" />
	</include>
	
	<group ns="/p3dx">
	
		<!-- Load the URDF into the ROS Parameter Server -->
		
		<param name="robot_description"
			command="$(find xacro)/xacro.py --inorder '$(find p3dx_description)/urdf/pioneer3dx.xacro'" />
	
		<!-- Run a python script to the send a service call to gazebo_ros to spawn 
			a URDF robot -->
		<node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model"
			respawn="false" output="screen" args="-urdf -param robot_description -model p3dx" />
		
		<rosparam command="load" file="$(find p3dx_control)/config/control.yaml" />
		
		<node name="base_controller_spawner" pkg="controller_manager" type="spawner"
	        args="--namespace=/p3dx
	        p3dx_joint_publisher
	        p3dx_velocity_controller
	        --shutdown-timeout 3"
	        output="screen"/>
	
		<!-- ros_control p3rd launch file -->
		<!-- <include file="$(find p3dx_control)/launch/control.launch" /> -->
	</group>

</launch>

Now you launch the simulation again and execute the following command rosrun teleop_twist_keyboard teleop_twist_keyboard.py cmd_vel:=/p3dx/p3dx_velocity_controller/cmd_vel . You’ll see that the robot stops when you release the key. You can also change the time for timeout in the control.yaml file.

 

If you are interested in this topic, please check our ROS control 101 course, which explains the ros controller much into detail.

 

Edit by: Tony Huang

 

—–

Did you like the video? If you did please give us a thumbs up and remember to subscribe to our channel and press the bell for a new video every day. Either you like it or not, please share your thoughts and questions in the comments area.

Masterclass 2023 batch2 blog banner

Check Out These Related Posts

129. ros2ai

129. ros2ai

I would like to dedicate this episode to all the ROS Developers who believe that ChatGPT or...

read more

0 Comments

Submit a Comment

Your email address will not be published.

This site uses Akismet to reduce spam. Learn how your comment data is processed.

Pin It on Pinterest

Share This