Public Member Functions | Public Attributes | Static Public Attributes | Private Member Functions | Private Attributes | List of all members
controller::CasterController Class Reference

#include <caster_controller.h>

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

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 Member Functions inherited from pr2_controller_interface::Controller
 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 ()
 

Public Attributes

pr2_mechanism_model::JointStatecaster_
 
double drive_velocity_
 
double steer_velocity_
 
- Public Attributes inherited from pr2_controller_interface::Controller
std::vector< std::string > after_list_
 
 AFTER_ME
 
std::vector< std::string > before_list_
 
 BEFORE_ME
 
 CONSTRUCTED
 
 INITIALIZED
 
 RUNNING
 
enum pr2_controller_interface::Controller:: { ... }  state_
 

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

controller::CasterController::CasterController ( )

Definition at line 44 of file caster_controller.cpp.

controller::CasterController::~CasterController ( )

Definition at line 49 of file caster_controller.cpp.

Member Function Documentation

double controller::CasterController::getSteerPosition ( )
inline

Definition at line 89 of file caster_controller.h.

double controller::CasterController::getSteerVelocity ( )
inline

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.

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

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

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

Definition at line 92 of file caster_controller.h.

JointVelocityController controller::CasterController::caster_vel_
private

Definition at line 96 of file caster_controller.h.

ros::Subscriber controller::CasterController::drive_cmd_
private

Definition at line 98 of file caster_controller.h.

double controller::CasterController::drive_velocity_

Definition at line 87 of file caster_controller.h.

ros::NodeHandle controller::CasterController::node_
private

Definition at line 95 of file caster_controller.h.

ros::Subscriber controller::CasterController::steer_cmd_
private

Definition at line 97 of file caster_controller.h.

double controller::CasterController::steer_velocity_

Definition at line 86 of file caster_controller.h.

JointVelocityController controller::CasterController::wheel_l_vel_
private

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.

JointVelocityController controller::CasterController::wheel_r_vel_
private

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 Wed Jun 5 2019 19:34:08