controller::CasterController Class Reference

#include <caster_controller.h>

List of all members.

Public Member Functions

 CasterController ()
double getSteerPosition ()
double getSteerVelocity ()
bool init (pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
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)
void update ()
 ~CasterController ()

Public Attributes

pr2_mechanism_model::JointState * caster_
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 66 of file caster_controller.h.


Constructor & Destructor Documentation

controller::CasterController::CasterController (  ) 

Definition at line 41 of file caster_controller.cpp.

controller::CasterController::~CasterController (  ) 

Definition at line 46 of file caster_controller.cpp.


Member Function Documentation

double controller::CasterController::getSteerPosition (  )  [inline]

Definition at line 83 of file caster_controller.h.

double controller::CasterController::getSteerVelocity (  )  [inline]

Definition at line 84 of file caster_controller.h.

bool controller::CasterController::init ( pr2_mechanism_model::RobotState *  robot,
ros::NodeHandle &  n 
)

Definition at line 73 of file caster_controller.cpp.

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 50 of file caster_controller.cpp.

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

Definition at line 156 of file caster_controller.cpp.

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

Definition at line 151 of file caster_controller.cpp.

void controller::CasterController::update (  ) 

Definition at line 137 of file caster_controller.cpp.


Member Data Documentation

pr2_mechanism_model::JointState* controller::CasterController::caster_

Definition at line 86 of file caster_controller.h.

JointVelocityController controller::CasterController::caster_vel_ [private]

Definition at line 90 of file caster_controller.h.

ros::Subscriber controller::CasterController::drive_cmd_ [private]

Definition at line 92 of file caster_controller.h.

Definition at line 81 of file caster_controller.h.

ros::NodeHandle controller::CasterController::node_ [private]

Definition at line 89 of file caster_controller.h.

ros::Subscriber controller::CasterController::steer_cmd_ [private]

Definition at line 91 of file caster_controller.h.

Definition at line 80 of file caster_controller.h.

JointVelocityController controller::CasterController::wheel_l_vel_ [private]

Definition at line 90 of file caster_controller.h.

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

Definition at line 67 of file caster_controller.h.

JointVelocityController controller::CasterController::wheel_r_vel_ [private]

Definition at line 90 of file caster_controller.h.

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

Definition at line 66 of file caster_controller.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Friends Defines


pr2_mechanism_controllers
Author(s): Sachin Chita, John Hsu, Melonee Wise
autogenerated on Fri Jan 11 09:39:08 2013