#include <caster_controller.h>
|
| CasterController () |
|
double | getSteerPosition () |
|
double | getSteerVelocity () |
|
bool | init (pr2_mechanism_model::RobotState *robot_state, const std::string &caster_joint, const std::string &wheel_l_joint, const std::string &wheel_r_joint, const control_toolbox::Pid &caster_pid, const control_toolbox::Pid &wheel_pid) |
|
bool | init (pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n) |
|
void | update () |
|
| ~CasterController () |
|
| Controller () |
|
bool | getController (const std::string &name, int sched, ControllerType *&c) |
|
bool | initRequest (ControllerProvider *cp, pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n) |
|
bool | isRunning () |
|
void | starting (const ros::Time &time) |
|
virtual void | starting () |
|
bool | startRequest () |
|
void | stopping (const ros::Time &time) |
|
virtual void | stopping () |
|
bool | stopRequest () |
|
void | update (const ros::Time &time, const ros::Duration &period) |
|
void | updateRequest () |
|
virtual | ~Controller () |
|
Definition at line 69 of file caster_controller.h.
controller::CasterController::CasterController |
( |
| ) |
|
controller::CasterController::~CasterController |
( |
| ) |
|
double controller::CasterController::getSteerPosition |
( |
| ) |
|
|
inline |
double controller::CasterController::getSteerVelocity |
( |
| ) |
|
|
inline |
void controller::CasterController::setDriveCB |
( |
const std_msgs::Float64ConstPtr & |
msg | ) |
|
|
private |
void controller::CasterController::setSteerCB |
( |
const std_msgs::Float64ConstPtr & |
msg | ) |
|
|
private |
void controller::CasterController::update |
( |
void |
| ) |
|
|
virtual |
double controller::CasterController::drive_velocity_ |
double controller::CasterController::steer_velocity_ |
const double controller::CasterController::WHEEL_OFFSET = 0.049 |
|
static |
const double controller::CasterController::WHEEL_RADIUS = 0.079 |
|
static |
The documentation for this class was generated from the following files: