#include <ackermann_steering_bot.h>
|
| AckermannSteeringBot () |
|
ros::Duration | getPeriod () const |
|
ros::Time | getTime () const |
|
void | read () |
|
bool | startCallback (std_srvs::Empty::Request &, std_srvs::Empty::Response &) |
|
bool | stopCallback (std_srvs::Empty::Request &, std_srvs::Empty::Response &) |
|
void | write () |
|
virtual bool | checkForConflict (const std::list< ControllerInfo > &info) const |
|
virtual bool | checkForConflict (const std::list< ControllerInfo > &info) const |
|
virtual void | doSwitch (const std::list< ControllerInfo > &, const std::list< ControllerInfo > &) |
|
virtual void | doSwitch (const std::list< ControllerInfo > &, const std::list< ControllerInfo > &) |
|
virtual bool | init (ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh) |
|
virtual bool | prepareSwitch (const std::list< ControllerInfo > &start_list, const std::list< ControllerInfo > &stop_list) |
|
virtual bool | prepareSwitch (const std::list< ControllerInfo > &start_list, const std::list< ControllerInfo > &stop_list) |
|
virtual void | read (const ros::Time &time, const ros::Duration &period) |
|
virtual void | read (const ros::Time &time, const ros::Duration &period) |
|
| RobotHW () |
|
virtual void | write (const ros::Time &time, const ros::Duration &period) |
|
virtual void | write (const ros::Time &time, const ros::Duration &period) |
|
virtual | ~RobotHW () |
|
T * | get () |
|
std::vector< std::string > | getInterfaceResources (std::string iface_type) const |
|
std::vector< std::string > | getNames () const |
|
void | registerInterface (T *iface) |
|
void | registerInterfaceManager (InterfaceManager *iface_man) |
|
|
void | cleanUp () |
|
void | getJointNames (ros::NodeHandle &_nh) |
|
void | getSteerJointNames (ros::NodeHandle &_nh) |
|
void | getWheelJointNames (ros::NodeHandle &_nh) |
|
void | registerCommandJointInterfaceHandle (hardware_interface::JointStateInterface &_jnt_state_interface, hardware_interface::JointCommandInterface &_jnt_cmd_interface, const std::string _jnt_name, double &_jnt_cmd) |
|
void | registerHardwareInterfaces () |
|
void | registerInterfaceHandles (hardware_interface::JointStateInterface &_jnt_state_interface, hardware_interface::JointCommandInterface &_jnt_cmd_interface, const std::string _jnt_name, double &_jnt_pos, double &_jnt_vel, double &_jnt_eff, double &_jnt_cmd) |
|
void | registerJointStateInterfaceHandle (hardware_interface::JointStateInterface &_jnt_state_interface, const std::string _jnt_name, double &_jnt_pos, double &_jnt_vel, double &_jnt_eff) |
|
void | registerSteerInterface () |
|
void | registerWheelInterface () |
|
Definition at line 55 of file ackermann_steering_bot.h.
AckermannSteeringBot::AckermannSteeringBot |
( |
| ) |
|
|
inline |
void AckermannSteeringBot::cleanUp |
( |
| ) |
|
|
inlineprivate |
ros::Time AckermannSteeringBot::getTime |
( |
| ) |
const |
|
inline |
void AckermannSteeringBot::read |
( |
| ) |
|
|
inline |
void AckermannSteeringBot::registerHardwareInterfaces |
( |
| ) |
|
|
inlineprivate |
void AckermannSteeringBot::registerJointStateInterfaceHandle |
( |
hardware_interface::JointStateInterface & |
_jnt_state_interface, |
|
|
const std::string |
_jnt_name, |
|
|
double & |
_jnt_pos, |
|
|
double & |
_jnt_vel, |
|
|
double & |
_jnt_eff |
|
) |
| |
|
inlineprivate |
void AckermannSteeringBot::registerSteerInterface |
( |
| ) |
|
|
inlineprivate |
void AckermannSteeringBot::registerWheelInterface |
( |
| ) |
|
|
inlineprivate |
bool AckermannSteeringBot::startCallback |
( |
std_srvs::Empty::Request & |
, |
|
|
std_srvs::Empty::Response & |
|
|
) |
| |
|
inline |
bool AckermannSteeringBot::stopCallback |
( |
std_srvs::Empty::Request & |
, |
|
|
std_srvs::Empty::Response & |
|
|
) |
| |
|
inline |
void AckermannSteeringBot::write |
( |
| ) |
|
|
inline |
double AckermannSteeringBot::front_steer_jnt_eff_ |
|
private |
std::string AckermannSteeringBot::front_steer_jnt_name_ |
|
private |
double AckermannSteeringBot::front_steer_jnt_pos_ |
|
private |
double AckermannSteeringBot::front_steer_jnt_pos_cmd_ |
|
private |
double AckermannSteeringBot::front_steer_jnt_vel_ |
|
private |
std::string AckermannSteeringBot::ns_ |
|
private |
double AckermannSteeringBot::rear_wheel_jnt_eff_ |
|
private |
std::string AckermannSteeringBot::rear_wheel_jnt_name_ |
|
private |
double AckermannSteeringBot::rear_wheel_jnt_pos_ |
|
private |
double AckermannSteeringBot::rear_wheel_jnt_vel_ |
|
private |
double AckermannSteeringBot::rear_wheel_jnt_vel_cmd_ |
|
private |
bool AckermannSteeringBot::running_ |
|
private |
std::vector<double> AckermannSteeringBot::virtual_front_steer_jnt_eff_ |
|
private |
std::vector<std::string> AckermannSteeringBot::virtual_front_steer_jnt_names_ |
|
private |
std::vector<double> AckermannSteeringBot::virtual_front_steer_jnt_pos_ |
|
private |
std::vector<double> AckermannSteeringBot::virtual_front_steer_jnt_pos_cmd_ |
|
private |
std::vector<double> AckermannSteeringBot::virtual_front_steer_jnt_vel_ |
|
private |
std::vector<double> AckermannSteeringBot::virtual_front_wheel_jnt_eff_ |
|
private |
std::vector<std::string> AckermannSteeringBot::virtual_front_wheel_jnt_names_ |
|
private |
std::vector<double> AckermannSteeringBot::virtual_front_wheel_jnt_pos_ |
|
private |
std::vector<double> AckermannSteeringBot::virtual_front_wheel_jnt_vel_ |
|
private |
std::vector<double> AckermannSteeringBot::virtual_front_wheel_jnt_vel_cmd_ |
|
private |
std::vector<double> AckermannSteeringBot::virtual_rear_wheel_jnt_eff_ |
|
private |
std::vector<std::string> AckermannSteeringBot::virtual_rear_wheel_jnt_names_ |
|
private |
std::vector<double> AckermannSteeringBot::virtual_rear_wheel_jnt_pos_ |
|
private |
std::vector<double> AckermannSteeringBot::virtual_rear_wheel_jnt_vel_ |
|
private |
std::vector<double> AckermannSteeringBot::virtual_rear_wheel_jnt_vel_cmd_ |
|
private |
double AckermannSteeringBot::wheel_separation_h_ |
|
private |
double AckermannSteeringBot::wheel_separation_w_ |
|
private |
The documentation for this class was generated from the following file: