Public Member Functions | Public Attributes | Static Public Attributes | Private Member Functions | Private Attributes
controller::CasterController Class Reference

#include <caster_controller.h>

Inheritance diagram for controller::CasterController:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 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 ()

Public Attributes

pr2_mechanism_model::JointStatecaster_
double drive_velocity_
double steer_velocity_

Static Public Attributes

static const double WHEEL_OFFSET = 0.049
static const double WHEEL_RADIUS = 0.079

Private Member Functions

void setDriveCB (const std_msgs::Float64ConstPtr &msg)
void setSteerCB (const std_msgs::Float64ConstPtr &msg)

Private Attributes

JointVelocityController caster_vel_
ros::Subscriber drive_cmd_
ros::NodeHandle node_
ros::Subscriber steer_cmd_
JointVelocityController wheel_l_vel_
JointVelocityController wheel_r_vel_

Detailed Description

Definition at line 69 of file caster_controller.h.


Constructor & Destructor Documentation

Definition at line 44 of file caster_controller.cpp.

Definition at line 49 of file caster_controller.cpp.


Member Function Documentation

Definition at line 89 of file caster_controller.h.

Definition at line 90 of file caster_controller.h.

bool controller::CasterController::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 
)

Definition at line 53 of file caster_controller.cpp.

Implements pr2_controller_interface::Controller.

Definition at line 76 of file caster_controller.cpp.

void controller::CasterController::setDriveCB ( const std_msgs::Float64ConstPtr &  msg) [private]

Definition at line 159 of file caster_controller.cpp.

void controller::CasterController::setSteerCB ( const std_msgs::Float64ConstPtr &  msg) [private]

Definition at line 154 of file caster_controller.cpp.

void controller::CasterController::update ( void  ) [virtual]

Implements pr2_controller_interface::Controller.

Definition at line 140 of file caster_controller.cpp.


Member Data Documentation

Definition at line 92 of file caster_controller.h.

Definition at line 96 of file caster_controller.h.

Definition at line 98 of file caster_controller.h.

Definition at line 87 of file caster_controller.h.

Definition at line 95 of file caster_controller.h.

Definition at line 97 of file caster_controller.h.

Definition at line 86 of file caster_controller.h.

Definition at line 96 of file caster_controller.h.

const double controller::CasterController::WHEEL_OFFSET = 0.049 [static]

Definition at line 73 of file caster_controller.h.

Definition at line 96 of file caster_controller.h.

const double controller::CasterController::WHEEL_RADIUS = 0.079 [static]

Definition at line 72 of file caster_controller.h.


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


pr2_mechanism_controllers
Author(s): Sachin Chita, John Hsu, Melonee Wise
autogenerated on Thu Aug 27 2015 14:22:52