-
Notifications
You must be signed in to change notification settings - Fork 3
rocker_bogie_controller
Controller for rocker bogie drive wheel systems. Control is in the form of a velocity command, that is split then sent on the two steer and the four wheels of a rocker bogie drive configuration. Odometry is computed from the feedback from the hardware, and published.
The controller is created based on diff_drive_controller
so it is compatible with ros_controller
.
You can easily activate this controller same as other ros_controllers
with which you should be familiar.
The controller works with a velocity twist from which it extracts the x component of the linear velocity and the z component of the angular velocity. Velocities on other components are ignored.
The controller works with steer joints through a position interface and wheel joints through a velocity interface.
- /fr01_rocker_bogie_controller/cmd_vel (geometry_msgs/Twist)
- Velocity command.
-
/fr01_rocker_bogie_controller/odom (nav_msgs/Odometry)
-
Odometry computed from the hardware feedback.
-
Not properly implemented yet.
-
/tf (tf/tfMessage)
-
Transform from odom to base_footprint
-
Not properly implemented yet.
See the following yaml file example and please feel requirements from its parameter names.
rosed fr01_control fr01_rocker_bogie_controller.yaml
#fr01:
# Publish all joint states -----------------------------------
joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: 50
# Wheel & Steer (rocker_bogie_controller should be used without namespace)
fr01_rocker_bogie_controller:
type : "rocker_bogie_controller/RockerBogieController"
left_wheel : ['wheel_left_front_joint', 'wheel_left_middle_joint', 'wheel_left_back_joint']
right_wheel : ['wheel_right_front_joint', 'wheel_right_middle_joint', 'wheel_right_back_joint']
left_steer : ['steer_left_front_joint', 'steer_left_back_joint']
right_steer : ['steer_right_front_joint', 'steer_right_back_joint']
publish_rate: 100
pose_covariance_diagonal : [0.00001, 0.00001, 1000000000000.0, 1000000000000.0, 1000000000000.0, 0.001]
twist_covariance_diagonal: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
wheel_separation_multiplier: 1.0
wheel_radius_multiplier : 1.0
cmd_vel_timeout: 20
base_frame_id: base_footprint
enable_odom_tf: true
wheel_separation_w : 0.26
wheel_separation_h : 0.4
wheel_radius : 0.3
linear:
x:
has_velocity_limits : true
max_velocity : 0.9 # m/s
min_velocity : -0.9 # m/s
has_acceleration_limits: true
max_acceleration : 1.7 # m/s^2
min_acceleration : -0.4 # m/s^2
angular:
z:
has_velocity_limits : true
max_velocity : 0.5 # rad/s
has_acceleration_limits: true
max_acceleration : 1.5 # rad/s^2 # wheel_right_front_joint_position_controller:
- First, load parameters from
fr01_rocker_bogie_controller.yaml
. - Of course you can also create your own yaml.
- Next, spawn controller named
fr01_rocker_bogie_controller
. - Please do not specify namespace for now.
roslanch fr01_control fr01_sim_control.launch
<launch>
<!-- Load joint controller configurations from YAML file to parameter server -->
<!-- <rosparam file="$(find fr01_control)/config/fr01_diff_drive_controller.yaml" command="load"/> -->
<rosparam file="$(find fr01_control)/config/fr01_rocker_bogie_controller.yaml" command="load"/>
<!-- load the controllers -->
<node name="controller_spawner" pkg="controller_manager"
type="spawner" respawn="false"
output="screen"
args="fr01_rocker_bogie_controller
joint_state_controller
" />
<!-- convert joint states to TF transforms for rviz, etc -->
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"
respawn="false" output="screen">
<!-- <remap from="/joint_states" to="/fr01/joint_states" /> -->
</node>
</launch>