#include <steer_drive_controller.h>
Classes | |
struct | Commands |
Velocity command related: More... | |
Public Member Functions | |
bool | init (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh) |
Initialize controller. | |
void | starting (const ros::Time &time) |
Starts controller. | |
SteerDriveController () | |
void | stopping (const ros::Time &) |
Stops controller. | |
void | update (const ros::Time &time, const ros::Duration &period) |
Updates controller, i.e. computes the odometry and sets the new velocity commands. | |
Private Types | |
enum | INDEX_WHEEL { INDEX_RIGHT = 0, INDEX_LEFT = 1 } |
enum | INDX_STEER { INDX_STEER_FRNT = 0, INDX_STEER_BACK = 1 } |
enum | INDX_WHEEL { INDX_WHEEL_FRNT = 0, INDX_WHEEL_MID = 1, INDX_WHEEL_BACK = 2 } |
Private Member Functions | |
void | brake () |
Brakes the wheels, i.e. sets the velocity to 0. | |
void | cmdVelCallback (const geometry_msgs::Twist &command) |
Velocity command callback. | |
bool | setOdomParamsFromUrdf (ros::NodeHandle &root_nh, const std::string rear_wheel_name, const std::string front_steer_name, bool lookup_wheel_separation_h, bool lookup_wheel_radius) |
Sets odometry parameters from the URDF, i.e. the wheel radius and separation. | |
void | setOdomPubFields (ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh) |
Sets the odometry publishing fields. | |
Private Attributes | |
bool | allow_multiple_cmd_vel_publishers_ |
Whether to allow multiple publishers on cmd_vel topic or not: | |
std::string | base_frame_id_ |
Frame to use for the robot base: | |
double | cmd_vel_timeout_ |
Timeout to consider cmd_vel commands old: | |
realtime_tools::RealtimeBuffer < Commands > | command_ |
Commands | command_struct_ |
bool | enable_odom_tf_ |
Whether to publish odometry to tf or not: | |
hardware_interface::JointHandle | front_steer_joint_ |
Commands | last0_cmd_ |
Commands | last1_cmd_ |
Speed limiters: | |
ros::Time | last_state_publish_time_ |
SpeedLimiter | limiter_ang_ |
SpeedLimiter | limiter_lin_ |
std::string | name_ |
std::string | ns_ |
std::string | odom_frame_id_ |
Frame to use for odometry and odom tf: | |
boost::shared_ptr < realtime_tools::RealtimePublisher < nav_msgs::Odometry > > | odom_pub_ |
Odometry related: | |
Odometry | odometry_ |
bool | open_loop_ |
ros::Duration | publish_period_ |
Odometry related: | |
hardware_interface::JointHandle | rear_wheel_joint_ |
Hardware handles: | |
size_t | steer_joints_size_ |
Number of steer joints: | |
double | steer_pos_multiplier_ |
ros::Subscriber | sub_command_ |
boost::shared_ptr < realtime_tools::RealtimePublisher < tf::tfMessage > > | tf_odom_pub_ |
size_t | wheel_joints_size_ |
Number of wheel joints: | |
double | wheel_radius_ |
Wheel radius (assuming it's the same for the left and right wheels): | |
double | wheel_radius_multiplier_ |
double | wheel_separation_h_ |
Wheel separation, wrt the midpoint of the wheel width: | |
double | wheel_separation_h_multiplier_ |
Wheel separation and radius calibration multipliers: |
This class makes some assumptions on the model of the robot:
Definition at line 67 of file steer_drive_controller.h.
enum steer_drive_controller::SteerDriveController::INDEX_WHEEL [private] |
Definition at line 84 of file steer_drive_controller.h.
enum steer_drive_controller::SteerDriveController::INDX_STEER [private] |
Definition at line 79 of file steer_drive_controller.h.
enum steer_drive_controller::SteerDriveController::INDX_WHEEL [private] |
Definition at line 74 of file steer_drive_controller.h.
Definition at line 112 of file steer_drive_controller.cpp.
void steer_drive_controller::SteerDriveController::brake | ( | ) | [private] |
Brakes the wheels, i.e. sets the velocity to 0.
Definition at line 359 of file steer_drive_controller.cpp.
void steer_drive_controller::SteerDriveController::cmdVelCallback | ( | const geometry_msgs::Twist & | command | ) | [private] |
Velocity command callback.
command | Velocity command message (twist) |
Definition at line 368 of file steer_drive_controller.cpp.
bool steer_drive_controller::SteerDriveController::init | ( | hardware_interface::RobotHW * | robot_hw, |
ros::NodeHandle & | root_nh, | ||
ros::NodeHandle & | controller_nh | ||
) | [virtual] |
Initialize controller.
hw | Velocity joint interface for the wheels |
root_nh | Node handle at root namespace |
controller_nh | Node handle inside the controller namespace |
Reimplemented from controller_interface::MultiInterfaceController< hardware_interface::PositionJointInterface, hardware_interface::VelocityJointInterface >.
Definition at line 130 of file steer_drive_controller.cpp.
bool steer_drive_controller::SteerDriveController::setOdomParamsFromUrdf | ( | ros::NodeHandle & | root_nh, |
const std::string | rear_wheel_name, | ||
const std::string | front_steer_name, | ||
bool | lookup_wheel_separation_h, | ||
bool | lookup_wheel_radius | ||
) | [private] |
Sets odometry parameters from the URDF, i.e. the wheel radius and separation.
root_nh | Root node handle |
left_wheel_name | Name of the left wheel joint |
right_wheel_name | Name of the right wheel joint |
Definition at line 398 of file steer_drive_controller.cpp.
void steer_drive_controller::SteerDriveController::setOdomPubFields | ( | ros::NodeHandle & | root_nh, |
ros::NodeHandle & | controller_nh | ||
) | [private] |
Sets the odometry publishing fields.
root_nh | Root node handle |
controller_nh | Node handle inside the controller namespace |
Definition at line 473 of file steer_drive_controller.cpp.
void steer_drive_controller::SteerDriveController::starting | ( | const ros::Time & | time | ) | [virtual] |
Starts controller.
time | Current time |
Reimplemented from controller_interface::ControllerBase.
Definition at line 344 of file steer_drive_controller.cpp.
void steer_drive_controller::SteerDriveController::stopping | ( | const ros::Time & | ) | [virtual] |
Stops controller.
time | Current time |
Reimplemented from controller_interface::ControllerBase.
Definition at line 354 of file steer_drive_controller.cpp.
void steer_drive_controller::SteerDriveController::update | ( | const ros::Time & | time, |
const ros::Duration & | period | ||
) | [virtual] |
Updates controller, i.e. computes the odometry and sets the new velocity commands.
time | Current time |
period | Time since the last called to update |
Implements controller_interface::ControllerBase.
Definition at line 264 of file steer_drive_controller.cpp.
Whether to allow multiple publishers on cmd_vel topic or not:
Definition at line 166 of file steer_drive_controller.h.
std::string steer_drive_controller::SteerDriveController::base_frame_id_ [private] |
Frame to use for the robot base:
Definition at line 169 of file steer_drive_controller.h.
double steer_drive_controller::SteerDriveController::cmd_vel_timeout_ [private] |
Timeout to consider cmd_vel commands old:
Definition at line 163 of file steer_drive_controller.h.
realtime_tools::RealtimeBuffer<Commands> steer_drive_controller::SteerDriveController::command_ [private] |
Definition at line 142 of file steer_drive_controller.h.
Definition at line 143 of file steer_drive_controller.h.
Whether to publish odometry to tf or not:
Definition at line 175 of file steer_drive_controller.h.
hardware_interface::JointHandle steer_drive_controller::SteerDriveController::front_steer_joint_ [private] |
Definition at line 131 of file steer_drive_controller.h.
Definition at line 185 of file steer_drive_controller.h.
Speed limiters:
Definition at line 184 of file steer_drive_controller.h.
Definition at line 126 of file steer_drive_controller.h.
Definition at line 187 of file steer_drive_controller.h.
Definition at line 186 of file steer_drive_controller.h.
std::string steer_drive_controller::SteerDriveController::name_ [private] |
Definition at line 122 of file steer_drive_controller.h.
std::string steer_drive_controller::SteerDriveController::ns_ [private] |
Definition at line 190 of file steer_drive_controller.h.
std::string steer_drive_controller::SteerDriveController::odom_frame_id_ [private] |
Frame to use for odometry and odom tf:
Definition at line 172 of file steer_drive_controller.h.
boost::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::Odometry> > steer_drive_controller::SteerDriveController::odom_pub_ [private] |
Odometry related:
Definition at line 147 of file steer_drive_controller.h.
Definition at line 149 of file steer_drive_controller.h.
bool steer_drive_controller::SteerDriveController::open_loop_ [private] |
Definition at line 127 of file steer_drive_controller.h.
Odometry related:
Definition at line 125 of file steer_drive_controller.h.
hardware_interface::JointHandle steer_drive_controller::SteerDriveController::rear_wheel_joint_ [private] |
Hardware handles:
Definition at line 130 of file steer_drive_controller.h.
size_t steer_drive_controller::SteerDriveController::steer_joints_size_ [private] |
Number of steer joints:
Definition at line 181 of file steer_drive_controller.h.
double steer_drive_controller::SteerDriveController::steer_pos_multiplier_ [private] |
Definition at line 160 of file steer_drive_controller.h.
Definition at line 144 of file steer_drive_controller.h.
boost::shared_ptr<realtime_tools::RealtimePublisher<tf::tfMessage> > steer_drive_controller::SteerDriveController::tf_odom_pub_ [private] |
Definition at line 148 of file steer_drive_controller.h.
size_t steer_drive_controller::SteerDriveController::wheel_joints_size_ [private] |
Number of wheel joints:
Definition at line 178 of file steer_drive_controller.h.
double steer_drive_controller::SteerDriveController::wheel_radius_ [private] |
Wheel radius (assuming it's the same for the left and right wheels):
Definition at line 155 of file steer_drive_controller.h.
Definition at line 159 of file steer_drive_controller.h.
double steer_drive_controller::SteerDriveController::wheel_separation_h_ [private] |
Wheel separation, wrt the midpoint of the wheel width:
Definition at line 152 of file steer_drive_controller.h.
Wheel separation and radius calibration multipliers:
Definition at line 158 of file steer_drive_controller.h.