Classes | Public Member Functions | Private Member Functions | Private Attributes | List of all members
ackermann_controller::AckermannController Class Reference

#include <ackermann_controller.h>

Inheritance diagram for ackermann_controller::AckermannController:
Inheritance graph
[legend]

Classes

struct  Commands
 

Public Member Functions

 AckermannController ()
 
bool init (hardware_interface::RobotHW *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::VelocityJointInterface, hardware_interface::JointStateInterface, hardware_interface::PositionJointInterface >
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 ()
 
void cmdVelCallback (const geometry_msgs::Twist &command)
 
std::vector< std::string > getJointNames (ros::NodeHandle &controller_nh, const std::string &param)
 
boost::shared_ptr< urdf::ModelInterface > getURDFModel (const ros::NodeHandle &nh)
 
bool initParams (ros::NodeHandle &controller_nh)
 
void moveRobot (const ros::Time &time, const ros::Duration &period)
 
void setOdomPubFields (ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
 
void updateOdometry (const ros::Time &time, const ros::Duration &period)
 

Private Attributes

std::string base_frame_id_
 
std::string base_link_
 
double cmd_vel_timeout_
 
realtime_tools::RealtimeBuffer< Commandscommand_
 
Commands command_struct_
 
bool enable_odom_tf_
 
Commands last0_cmd_
 
Commands last1_cmd_
 
ros::Time last_state_publish_time_
 
ackermann_controller::SpeedLimiter limiter_
 
std::string name_
 
std::string odom_frame_id_
 
boost::shared_ptr< realtime_tools::RealtimePublisher< nav_msgs::Odometry > > odom_pub_
 
ackermann_controller::Odometry odometry_
 
std::vector< Wheelodometry_joints_
 
bool open_loop_
 
ros::Duration publish_period_
 
std::vector< ActuatedWheelspinning_joints_
 
bool steering_angle_instead_of_angular_speed_
 
std::vector< ActuatedJointsteering_joints_
 
ros::Subscriber sub_command_
 
boost::shared_ptr< realtime_tools::RealtimePublisher< tf::tfMessage > > tf_odom_pub_
 
int velocity_rolling_window_size_
 
double wheelbase_
 

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::VelocityJointInterface, hardware_interface::JointStateInterface, hardware_interface::PositionJointInterface >
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::VelocityJointInterface, hardware_interface::JointStateInterface, hardware_interface::PositionJointInterface >
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::VelocityJointInterface, hardware_interface::JointStateInterface, hardware_interface::PositionJointInterface >
bool allow_optional_interfaces_
 
hardware_interface::RobotHW robot_hw_ctrl_
 

Detailed Description

Definition at line 25 of file ackermann_controller.h.

Constructor & Destructor Documentation

ackermann_controller::AckermannController::AckermannController ( )

Definition at line 20 of file ackermann_controller.cpp.

Member Function Documentation

void ackermann_controller::AckermannController::brake ( )
private

Definition at line 215 of file ackermann_controller.cpp.

void ackermann_controller::AckermannController::cmdVelCallback ( const geometry_msgs::Twist &  command)
private

Definition at line 226 of file ackermann_controller.cpp.

std::vector< std::string > ackermann_controller::AckermannController::getJointNames ( ros::NodeHandle controller_nh,
const std::string &  param 
)
private

Definition at line 319 of file ackermann_controller.cpp.

boost::shared_ptr< urdf::ModelInterface > ackermann_controller::AckermannController::getURDFModel ( const ros::NodeHandle nh)
private

Definition at line 304 of file ackermann_controller.cpp.

bool ackermann_controller::AckermannController::init ( hardware_interface::RobotHW hw,
ros::NodeHandle root_nh,
ros::NodeHandle controller_nh 
)
virtual

Initialize controller.

Parameters
hwJoint interface
root_nhNode handle at root namespace
controller_nhNode handle inside the controller namespace

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

Definition at line 34 of file ackermann_controller.cpp.

bool ackermann_controller::AckermannController::initParams ( ros::NodeHandle controller_nh)
private

Definition at line 248 of file ackermann_controller.cpp.

void ackermann_controller::AckermannController::moveRobot ( const ros::Time time,
const ros::Duration period 
)
private

Definition at line 153 of file ackermann_controller.cpp.

void ackermann_controller::AckermannController::setOdomPubFields ( ros::NodeHandle root_nh,
ros::NodeHandle controller_nh 
)
private

Definition at line 364 of file ackermann_controller.cpp.

void ackermann_controller::AckermannController::starting ( const ros::Time time)
virtual

Starts controller.

Parameters
timeCurrent time

Reimplemented from controller_interface::ControllerBase.

Definition at line 200 of file ackermann_controller.cpp.

void ackermann_controller::AckermannController::stopping ( const ros::Time )
virtual

Stops controller.

Parameters
timeCurrent time

Reimplemented from controller_interface::ControllerBase.

Definition at line 210 of file ackermann_controller.cpp.

void ackermann_controller::AckermannController::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 106 of file ackermann_controller.cpp.

void ackermann_controller::AckermannController::updateOdometry ( const ros::Time time,
const ros::Duration period 
)
private

Definition at line 112 of file ackermann_controller.cpp.

Member Data Documentation

std::string ackermann_controller::AckermannController::base_frame_id_
private

Definition at line 98 of file ackermann_controller.h.

std::string ackermann_controller::AckermannController::base_link_
private

Definition at line 99 of file ackermann_controller.h.

double ackermann_controller::AckermannController::cmd_vel_timeout_
private

Definition at line 95 of file ackermann_controller.h.

realtime_tools::RealtimeBuffer<Commands> ackermann_controller::AckermannController::command_
private

Definition at line 85 of file ackermann_controller.h.

Commands ackermann_controller::AckermannController::command_struct_
private

Definition at line 86 of file ackermann_controller.h.

bool ackermann_controller::AckermannController::enable_odom_tf_
private

Definition at line 100 of file ackermann_controller.h.

Commands ackermann_controller::AckermannController::last0_cmd_
private

Definition at line 103 of file ackermann_controller.h.

Commands ackermann_controller::AckermannController::last1_cmd_
private

Definition at line 102 of file ackermann_controller.h.

ros::Time ackermann_controller::AckermannController::last_state_publish_time_
private

Definition at line 69 of file ackermann_controller.h.

ackermann_controller::SpeedLimiter ackermann_controller::AckermannController::limiter_
private

Definition at line 104 of file ackermann_controller.h.

std::string ackermann_controller::AckermannController::name_
private

Definition at line 66 of file ackermann_controller.h.

std::string ackermann_controller::AckermannController::odom_frame_id_
private

Definition at line 97 of file ackermann_controller.h.

boost::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::Odometry> > ackermann_controller::AckermannController::odom_pub_
private

Definition at line 89 of file ackermann_controller.h.

ackermann_controller::Odometry ackermann_controller::AckermannController::odometry_
private

Definition at line 91 of file ackermann_controller.h.

std::vector<Wheel> ackermann_controller::AckermannController::odometry_joints_
private

Definition at line 73 of file ackermann_controller.h.

bool ackermann_controller::AckermannController::open_loop_
private

Definition at line 70 of file ackermann_controller.h.

ros::Duration ackermann_controller::AckermannController::publish_period_
private

Definition at line 68 of file ackermann_controller.h.

std::vector<ActuatedWheel> ackermann_controller::AckermannController::spinning_joints_
private

Definition at line 72 of file ackermann_controller.h.

bool ackermann_controller::AckermannController::steering_angle_instead_of_angular_speed_
private

Definition at line 93 of file ackermann_controller.h.

std::vector<ActuatedJoint> ackermann_controller::AckermannController::steering_joints_
private

Definition at line 74 of file ackermann_controller.h.

ros::Subscriber ackermann_controller::AckermannController::sub_command_
private

Definition at line 87 of file ackermann_controller.h.

boost::shared_ptr<realtime_tools::RealtimePublisher<tf::tfMessage> > ackermann_controller::AckermannController::tf_odom_pub_
private

Definition at line 90 of file ackermann_controller.h.

int ackermann_controller::AckermannController::velocity_rolling_window_size_
private

Definition at line 96 of file ackermann_controller.h.

double ackermann_controller::AckermannController::wheelbase_
private

Definition at line 94 of file ackermann_controller.h.


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


ackermann_controller
Author(s): GĂ©rald Lelong
autogenerated on Mon Jun 10 2019 12:44:49