#include <ackermann_steering_bot.h>
|
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 58 of file ackermann_steering_bot.h.
◆ AckermannSteeringBot()
AckermannSteeringBot::AckermannSteeringBot |
( |
| ) |
|
|
inline |
◆ cleanUp()
void AckermannSteeringBot::cleanUp |
( |
| ) |
|
|
inlineprivate |
◆ getJointNames()
◆ getPeriod()
◆ getSteerJointNames()
◆ getTime()
ros::Time AckermannSteeringBot::getTime |
( |
| ) |
const |
|
inline |
◆ getWheelJointNames()
◆ read()
void AckermannSteeringBot::read |
( |
| ) |
|
|
inline |
◆ registerCommandJointInterfaceHandle()
◆ registerHardwareInterfaces()
void AckermannSteeringBot::registerHardwareInterfaces |
( |
| ) |
|
|
inlineprivate |
◆ registerInterfaceHandles()
◆ registerJointStateInterfaceHandle()
void AckermannSteeringBot::registerJointStateInterfaceHandle |
( |
hardware_interface::JointStateInterface & |
_jnt_state_interface, |
|
|
const std::string |
_jnt_name, |
|
|
double & |
_jnt_pos, |
|
|
double & |
_jnt_vel, |
|
|
double & |
_jnt_eff |
|
) |
| |
|
inlineprivate |
◆ registerSteerInterface()
void AckermannSteeringBot::registerSteerInterface |
( |
| ) |
|
|
inlineprivate |
◆ registerWheelInterface()
void AckermannSteeringBot::registerWheelInterface |
( |
| ) |
|
|
inlineprivate |
◆ startCallback()
bool AckermannSteeringBot::startCallback |
( |
std_srvs::Empty::Request & |
, |
|
|
std_srvs::Empty::Response & |
|
|
) |
| |
|
inline |
◆ stopCallback()
bool AckermannSteeringBot::stopCallback |
( |
std_srvs::Empty::Request & |
, |
|
|
std_srvs::Empty::Response & |
|
|
) |
| |
|
inline |
◆ write()
void AckermannSteeringBot::write |
( |
| ) |
|
|
inline |
◆ front_steer_jnt_eff_
double AckermannSteeringBot::front_steer_jnt_eff_ |
|
private |
◆ front_steer_jnt_name_
std::string AckermannSteeringBot::front_steer_jnt_name_ |
|
private |
◆ front_steer_jnt_pos_
double AckermannSteeringBot::front_steer_jnt_pos_ |
|
private |
◆ front_steer_jnt_pos_cmd_
double AckermannSteeringBot::front_steer_jnt_pos_cmd_ |
|
private |
◆ front_steer_jnt_pos_cmd_interface_
◆ front_steer_jnt_vel_
double AckermannSteeringBot::front_steer_jnt_vel_ |
|
private |
◆ jnt_state_interface_
◆ nh_
◆ ns_
std::string AckermannSteeringBot::ns_ |
|
private |
◆ rear_wheel_jnt_eff_
double AckermannSteeringBot::rear_wheel_jnt_eff_ |
|
private |
◆ rear_wheel_jnt_name_
std::string AckermannSteeringBot::rear_wheel_jnt_name_ |
|
private |
◆ rear_wheel_jnt_pos_
double AckermannSteeringBot::rear_wheel_jnt_pos_ |
|
private |
◆ rear_wheel_jnt_vel_
double AckermannSteeringBot::rear_wheel_jnt_vel_ |
|
private |
◆ rear_wheel_jnt_vel_cmd_
double AckermannSteeringBot::rear_wheel_jnt_vel_cmd_ |
|
private |
◆ rear_wheel_jnt_vel_cmd_interface_
◆ running_
bool AckermannSteeringBot::running_ |
|
private |
◆ start_srv_
◆ stop_srv_
◆ virtual_front_steer_jnt_eff_
std::vector<double> AckermannSteeringBot::virtual_front_steer_jnt_eff_ |
|
private |
◆ virtual_front_steer_jnt_names_
std::vector<std::string> AckermannSteeringBot::virtual_front_steer_jnt_names_ |
|
private |
◆ virtual_front_steer_jnt_pos_
std::vector<double> AckermannSteeringBot::virtual_front_steer_jnt_pos_ |
|
private |
◆ virtual_front_steer_jnt_pos_cmd_
std::vector<double> AckermannSteeringBot::virtual_front_steer_jnt_pos_cmd_ |
|
private |
◆ virtual_front_steer_jnt_vel_
std::vector<double> AckermannSteeringBot::virtual_front_steer_jnt_vel_ |
|
private |
◆ virtual_front_wheel_jnt_eff_
std::vector<double> AckermannSteeringBot::virtual_front_wheel_jnt_eff_ |
|
private |
◆ virtual_front_wheel_jnt_names_
std::vector<std::string> AckermannSteeringBot::virtual_front_wheel_jnt_names_ |
|
private |
◆ virtual_front_wheel_jnt_pos_
std::vector<double> AckermannSteeringBot::virtual_front_wheel_jnt_pos_ |
|
private |
◆ virtual_front_wheel_jnt_vel_
std::vector<double> AckermannSteeringBot::virtual_front_wheel_jnt_vel_ |
|
private |
◆ virtual_front_wheel_jnt_vel_cmd_
std::vector<double> AckermannSteeringBot::virtual_front_wheel_jnt_vel_cmd_ |
|
private |
◆ virtual_rear_wheel_jnt_eff_
std::vector<double> AckermannSteeringBot::virtual_rear_wheel_jnt_eff_ |
|
private |
◆ virtual_rear_wheel_jnt_names_
std::vector<std::string> AckermannSteeringBot::virtual_rear_wheel_jnt_names_ |
|
private |
◆ virtual_rear_wheel_jnt_pos_
std::vector<double> AckermannSteeringBot::virtual_rear_wheel_jnt_pos_ |
|
private |
◆ virtual_rear_wheel_jnt_vel_
std::vector<double> AckermannSteeringBot::virtual_rear_wheel_jnt_vel_ |
|
private |
◆ virtual_rear_wheel_jnt_vel_cmd_
std::vector<double> AckermannSteeringBot::virtual_rear_wheel_jnt_vel_cmd_ |
|
private |
◆ wheel_separation_h_
double AckermannSteeringBot::wheel_separation_h_ |
|
private |
◆ wheel_separation_w_
double AckermannSteeringBot::wheel_separation_w_ |
|
private |
The documentation for this class was generated from the following file: