Classes | Public Member Functions | Private Member Functions | Private Attributes | List of all members
ackermann_steering_controller::AckermannSteeringController Class Reference

#include <ackermann_steering_controller.h>

Inheritance diagram for ackermann_steering_controller::AckermannSteeringController:
Inheritance graph
[legend]

Classes

struct  Commands
 Velocity command related: More...
 

Public Member Functions

 AckermannSteeringController ()
 
bool init (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
 Initialize controller. More...
 
void starting (const ros::Time &time)
 Starts controller. More...
 
void stopping (const ros::Time &)
 Stops controller. More...
 
void update (const ros::Time &time, const ros::Duration &period)
 Updates controller, i.e. computes the odometry and sets the new velocity commands. More...
 
- Public Member Functions inherited from controller_interface::MultiInterfaceController< hardware_interface::PositionJointInterface, hardware_interface::VelocityJointInterface >
virtual bool init (hardware_interface::RobotHW *, ros::NodeHandle &)
 
 MultiInterfaceController (bool allow_optional_interfaces=false)
 
virtual ~MultiInterfaceController ()
 
- Public Member Functions inherited from controller_interface::ControllerBase
 ControllerBase ()
 
bool isRunning ()
 
bool isRunning ()
 
bool startRequest (const ros::Time &time)
 
bool startRequest (const ros::Time &time)
 
bool stopRequest (const ros::Time &time)
 
bool stopRequest (const ros::Time &time)
 
void updateRequest (const ros::Time &time, const ros::Duration &period)
 
void updateRequest (const ros::Time &time, const ros::Duration &period)
 
virtual ~ControllerBase ()
 

Private Member Functions

void brake ()
 Brakes the wheels, i.e. sets the velocity to 0. More...
 
void cmdVelCallback (const geometry_msgs::Twist &command)
 Velocity command callback. More...
 
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. More...
 
void setOdomPubFields (ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
 Sets the odometry publishing fields. More...
 

Private Attributes

bool allow_multiple_cmd_vel_publishers_
 Whether to allow multiple publishers on cmd_vel topic or not: More...
 
std::string base_frame_id_
 Frame to use for the robot base: More...
 
double cmd_vel_timeout_
 Timeout to consider cmd_vel commands old: More...
 
realtime_tools::RealtimeBuffer< Commandscommand_
 
Commands command_struct_
 
bool enable_odom_tf_
 Whether to publish odometry to tf or not: More...
 
hardware_interface::JointHandle front_steer_joint_
 
Commands last0_cmd_
 
Commands last1_cmd_
 Speed limiters: More...
 
ros::Time last_state_publish_time_
 
diff_drive_controller::SpeedLimiter limiter_ang_
 
diff_drive_controller::SpeedLimiter limiter_lin_
 
std::string name_
 
std::string odom_frame_id_
 Frame to use for odometry and odom tf: More...
 
boost::shared_ptr< realtime_tools::RealtimePublisher< nav_msgs::Odometry > > odom_pub_
 Odometry related: More...
 
Odometry odometry_
 
bool open_loop_
 
ros::Duration publish_period_
 Odometry related: More...
 
hardware_interface::JointHandle rear_wheel_joint_
 Hardware handles: More...
 
size_t steer_joints_size_
 Number of steer joints: More...
 
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: More...
 
double wheel_radius_
 Wheel radius (assuming it's the same for the left and right wheels): More...
 
double wheel_radius_multiplier_
 
double wheel_separation_h_
 Wheel separation, wrt the midpoint of the wheel width: More...
 
double wheel_separation_h_multiplier_
 Wheel separation and radius calibration multipliers: More...
 

Additional Inherited Members

- Public Types inherited from controller_interface::ControllerBase
typedef std::vector< hardware_interface::InterfaceResourcesClaimedResources
 
- Public Attributes inherited from controller_interface::ControllerBase
 CONSTRUCTED
 
 INITIALIZED
 
 RUNNING
 
enum controller_interface::ControllerBase:: { ... }  state_
 
- Protected Member Functions inherited from controller_interface::MultiInterfaceController< hardware_interface::PositionJointInterface, hardware_interface::VelocityJointInterface >
virtual bool initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources)
 
- Static Protected Member Functions inherited from controller_interface::MultiInterfaceController< hardware_interface::PositionJointInterface, hardware_interface::VelocityJointInterface >
static void clearClaims (hardware_interface::RobotHW *robot_hw)
 
static void extractInterfaceResources (hardware_interface::RobotHW *robot_hw_in, hardware_interface::RobotHW *robot_hw_out)
 
static bool hasRequiredInterfaces (hardware_interface::RobotHW *robot_hw)
 
static void populateClaimedResources (hardware_interface::RobotHW *robot_hw, ClaimedResources &claimed_resources)
 
- Protected Attributes inherited from controller_interface::MultiInterfaceController< hardware_interface::PositionJointInterface, hardware_interface::VelocityJointInterface >
bool allow_optional_interfaces_
 
hardware_interface::RobotHW robot_hw_ctrl_
 

Detailed Description

This class makes some assumptions on the model of the robot:

Definition at line 64 of file ackermann_steering_controller.h.

Constructor & Destructor Documentation

ackermann_steering_controller::AckermannSteeringController::AckermannSteeringController ( )

Definition at line 111 of file ackermann_steering_controller.cpp.

Member Function Documentation

void ackermann_steering_controller::AckermannSteeringController::brake ( )
private

Brakes the wheels, i.e. sets the velocity to 0.

Definition at line 357 of file ackermann_steering_controller.cpp.

void ackermann_steering_controller::AckermannSteeringController::cmdVelCallback ( const geometry_msgs::Twist &  command)
private

Velocity command callback.

Parameters
commandVelocity command message (twist)

Definition at line 366 of file ackermann_steering_controller.cpp.

bool ackermann_steering_controller::AckermannSteeringController::init ( hardware_interface::RobotHW robot_hw,
ros::NodeHandle root_nh,
ros::NodeHandle controller_nh 
)
virtual

Initialize controller.

Parameters
hwVelocity joint interface for the wheels
root_nhNode handle at root namespace
controller_nhNode handle inside the controller namespace

Reimplemented from controller_interface::MultiInterfaceController< hardware_interface::PositionJointInterface, hardware_interface::VelocityJointInterface >.

Definition at line 128 of file ackermann_steering_controller.cpp.

bool ackermann_steering_controller::AckermannSteeringController::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.

Parameters
root_nhRoot node handle
left_wheel_nameName of the left wheel joint
right_wheel_nameName of the right wheel joint

Definition at line 396 of file ackermann_steering_controller.cpp.

void ackermann_steering_controller::AckermannSteeringController::setOdomPubFields ( ros::NodeHandle root_nh,
ros::NodeHandle controller_nh 
)
private

Sets the odometry publishing fields.

Parameters
root_nhRoot node handle
controller_nhNode handle inside the controller namespace

Definition at line 471 of file ackermann_steering_controller.cpp.

void ackermann_steering_controller::AckermannSteeringController::starting ( const ros::Time time)
virtual

Starts controller.

Parameters
timeCurrent time

Reimplemented from controller_interface::ControllerBase.

Definition at line 342 of file ackermann_steering_controller.cpp.

void ackermann_steering_controller::AckermannSteeringController::stopping ( const ros::Time )
virtual

Stops controller.

Parameters
timeCurrent time

Reimplemented from controller_interface::ControllerBase.

Definition at line 352 of file ackermann_steering_controller.cpp.

void ackermann_steering_controller::AckermannSteeringController::update ( const ros::Time time,
const ros::Duration period 
)
virtual

Updates controller, i.e. computes the odometry and sets the new velocity commands.

Parameters
timeCurrent time
periodTime since the last called to update

Implements controller_interface::ControllerBase.

Definition at line 262 of file ackermann_steering_controller.cpp.

Member Data Documentation

bool ackermann_steering_controller::AckermannSteeringController::allow_multiple_cmd_vel_publishers_
private

Whether to allow multiple publishers on cmd_vel topic or not:

Definition at line 147 of file ackermann_steering_controller.h.

std::string ackermann_steering_controller::AckermannSteeringController::base_frame_id_
private

Frame to use for the robot base:

Definition at line 150 of file ackermann_steering_controller.h.

double ackermann_steering_controller::AckermannSteeringController::cmd_vel_timeout_
private

Timeout to consider cmd_vel commands old:

Definition at line 144 of file ackermann_steering_controller.h.

realtime_tools::RealtimeBuffer<Commands> ackermann_steering_controller::AckermannSteeringController::command_
private

Definition at line 123 of file ackermann_steering_controller.h.

Commands ackermann_steering_controller::AckermannSteeringController::command_struct_
private

Definition at line 124 of file ackermann_steering_controller.h.

bool ackermann_steering_controller::AckermannSteeringController::enable_odom_tf_
private

Whether to publish odometry to tf or not:

Definition at line 156 of file ackermann_steering_controller.h.

hardware_interface::JointHandle ackermann_steering_controller::AckermannSteeringController::front_steer_joint_
private

Definition at line 112 of file ackermann_steering_controller.h.

Commands ackermann_steering_controller::AckermannSteeringController::last0_cmd_
private

Definition at line 166 of file ackermann_steering_controller.h.

Commands ackermann_steering_controller::AckermannSteeringController::last1_cmd_
private

Speed limiters:

Definition at line 165 of file ackermann_steering_controller.h.

ros::Time ackermann_steering_controller::AckermannSteeringController::last_state_publish_time_
private

Definition at line 107 of file ackermann_steering_controller.h.

diff_drive_controller::SpeedLimiter ackermann_steering_controller::AckermannSteeringController::limiter_ang_
private

Definition at line 168 of file ackermann_steering_controller.h.

diff_drive_controller::SpeedLimiter ackermann_steering_controller::AckermannSteeringController::limiter_lin_
private

Definition at line 167 of file ackermann_steering_controller.h.

std::string ackermann_steering_controller::AckermannSteeringController::name_
private

Definition at line 103 of file ackermann_steering_controller.h.

std::string ackermann_steering_controller::AckermannSteeringController::odom_frame_id_
private

Frame to use for odometry and odom tf:

Definition at line 153 of file ackermann_steering_controller.h.

boost::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::Odometry> > ackermann_steering_controller::AckermannSteeringController::odom_pub_
private

Odometry related:

Definition at line 128 of file ackermann_steering_controller.h.

Odometry ackermann_steering_controller::AckermannSteeringController::odometry_
private

Definition at line 130 of file ackermann_steering_controller.h.

bool ackermann_steering_controller::AckermannSteeringController::open_loop_
private

Definition at line 108 of file ackermann_steering_controller.h.

ros::Duration ackermann_steering_controller::AckermannSteeringController::publish_period_
private

Odometry related:

Definition at line 106 of file ackermann_steering_controller.h.

hardware_interface::JointHandle ackermann_steering_controller::AckermannSteeringController::rear_wheel_joint_
private

Hardware handles:

Definition at line 111 of file ackermann_steering_controller.h.

size_t ackermann_steering_controller::AckermannSteeringController::steer_joints_size_
private

Number of steer joints:

Definition at line 162 of file ackermann_steering_controller.h.

double ackermann_steering_controller::AckermannSteeringController::steer_pos_multiplier_
private

Definition at line 141 of file ackermann_steering_controller.h.

ros::Subscriber ackermann_steering_controller::AckermannSteeringController::sub_command_
private

Definition at line 125 of file ackermann_steering_controller.h.

boost::shared_ptr<realtime_tools::RealtimePublisher<tf::tfMessage> > ackermann_steering_controller::AckermannSteeringController::tf_odom_pub_
private

Definition at line 129 of file ackermann_steering_controller.h.

size_t ackermann_steering_controller::AckermannSteeringController::wheel_joints_size_
private

Number of wheel joints:

Definition at line 159 of file ackermann_steering_controller.h.

double ackermann_steering_controller::AckermannSteeringController::wheel_radius_
private

Wheel radius (assuming it's the same for the left and right wheels):

Definition at line 136 of file ackermann_steering_controller.h.

double ackermann_steering_controller::AckermannSteeringController::wheel_radius_multiplier_
private

Definition at line 140 of file ackermann_steering_controller.h.

double ackermann_steering_controller::AckermannSteeringController::wheel_separation_h_
private

Wheel separation, wrt the midpoint of the wheel width:

Definition at line 133 of file ackermann_steering_controller.h.

double ackermann_steering_controller::AckermannSteeringController::wheel_separation_h_multiplier_
private

Wheel separation and radius calibration multipliers:

Definition at line 139 of file ackermann_steering_controller.h.


The documentation for this class was generated from the following files:


ackermann_steering_controller
Author(s): Masaru Morita
autogenerated on Sat Apr 18 2020 03:58:07