$search

controller::Pr2BaseController Class Reference

#include <pr2_base_controller.h>

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

List of all members.

Public Member Functions

geometry_msgs::Twist getCommand ()
 Returns the current position command.
bool init (pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
 Pr2BaseController ()
 Default Constructor of the Pr2BaseController class.
void setCommand (const geometry_msgs::Twist &cmd_vel)
void setDesiredCasterSteer ()
 set the desired caster steer
void setJointCommands ()
 set the joint commands
void starting ()
void update ()
 (a) Updates commands to caster and wheels. Called every timestep in realtime
 ~Pr2BaseController ()
 Destructor of the Pr2BaseController class.

Public Attributes

BaseKinematics base_kin_
 class where the robot's information is computed and stored
pthread_mutex_t pr2_base_controller_lock_
 mutex lock for setting and getting commands

Private Member Functions

void commandCallback (const geometry_msgs::TwistConstPtr &msg)
 deal with Twist commands
void computeDesiredCasterSteer (const double &dT)
 computes the desired caster speeds given the desired base speed
void computeDesiredWheelSpeeds ()
 computes the desired wheel speeds given the desired base speed
void computeJointCommands (const double &dT)
 computes the desired caster steers and wheel speeds
geometry_msgs::Twist interpolateCommand (const geometry_msgs::Twist &start, const geometry_msgs::Twist &end, const geometry_msgs::Twist &max_rate, const double &dT)
 interpolates velocities within a given time based on maximum accelerations
void publishState (const ros::Time &current_time)
 Publish the state.
void setDesiredWheelSpeeds ()
 sends the desired wheel speeds to the wheel controllers
void updateJointControllers ()
 tells the wheel and caster controllers to update their speeds

Private Attributes

double alpha_stall_
 low pass filter value used for finding stalls
geometry_msgs::Twist base_vel_msg_
 callback message, used to remember where the base is commanded to go
std::vector< boost::shared_ptr
< JointVelocityController > > 
caster_controller_
 vector that stores the caster controllers
std::vector< control_toolbox::Pidcaster_position_pid_
 The pid controllers for caster position.
filters::MultiChannelTransferFunctionFilter
< double > 
caster_vel_filter_
ros::Time cmd_received_timestamp_
 timestamp corresponding to when the command received by the node
ros::Subscriber cmd_sub_
ros::Subscriber cmd_sub_deprecated_
geometry_msgs::Twist cmd_vel_
 speed command vector used internally to represent the current commanded speed
double cmd_vel_rot_eps_
 minimum rotational velocity value allowable
geometry_msgs::Twist cmd_vel_t_
 Input speed command vector represents the desired speed requested by the node. Note that this may differ from the current commanded speed due to acceleration limits imposed by the controller.
double cmd_vel_trans_eps_
 minimum tranlational velocity value allowable
geometry_msgs::Twist desired_vel_
 Input speed command vector represents the desired speed requested by the node.
double eps_
 generic epsilon value that is used as a minimum or maximum allowable input value
std::vector< double > filtered_velocity_
double kp_caster_steer_
 local gain used for speed control of the caster (to achieve resultant position control)
ros::Time last_publish_time_
 Time interval between state publishing.
ros::Time last_time_
 time corresponding to when update was last called
geometry_msgs::Twist max_accel_
 acceleration limits specified externally
double max_rotational_velocity_
 maximum rotational velocity magnitude allowable
double max_translational_velocity_
 maximum translational velocity magnitude allowable
geometry_msgs::Twist max_vel_
 velocity limits specified externally
bool new_cmd_available_
 true when new command received by node
ros::NodeHandle node_
bool publish_state_
ros::NodeHandle root_handle_
double state_publish_rate_
double state_publish_time_
 Time interval between state publishing.
boost::scoped_ptr
< realtime_tools::RealtimePublisher
< pr2_mechanism_controllers::BaseControllerState > > 
state_publisher_
 publishes information about the caster and wheel controllers
double timeout_
 timeout specifying time that the controller waits before setting the current velocity command to zero
std::vector< boost::shared_ptr
< JointVelocityController > > 
wheel_controller_
 vector that stores the wheel controllers

Detailed Description

Definition at line 55 of file pr2_base_controller.h.


Constructor & Destructor Documentation

controller::Pr2BaseController::Pr2BaseController (  ) 

Default Constructor of the Pr2BaseController class.

Definition at line 47 of file pr2_base_controller.cpp.

controller::Pr2BaseController::~Pr2BaseController (  ) 

Destructor of the Pr2BaseController class.

Definition at line 68 of file pr2_base_controller.cpp.


Member Function Documentation

void controller::Pr2BaseController::commandCallback ( const geometry_msgs::TwistConstPtr msg  )  [private]

deal with Twist commands

Definition at line 467 of file pr2_base_controller.cpp.

void controller::Pr2BaseController::computeDesiredCasterSteer ( const double &  dT  )  [private]

computes the desired caster speeds given the desired base speed

Definition at line 373 of file pr2_base_controller.cpp.

void controller::Pr2BaseController::computeDesiredWheelSpeeds (  )  [private]

computes the desired wheel speeds given the desired base speed

Definition at line 422 of file pr2_base_controller.cpp.

void controller::Pr2BaseController::computeJointCommands ( const double &  dT  )  [private]

computes the desired caster steers and wheel speeds

Definition at line 357 of file pr2_base_controller.cpp.

geometry_msgs::Twist controller::Pr2BaseController::getCommand (  ) 

Returns the current position command.

Returns:
Current velocity command

Definition at line 253 of file pr2_base_controller.cpp.

bool controller::Pr2BaseController::init ( pr2_mechanism_model::RobotState robot,
ros::NodeHandle n 
) [virtual]

Implements pr2_controller_interface::Controller.

Definition at line 74 of file pr2_base_controller.cpp.

geometry_msgs::Twist controller::Pr2BaseController::interpolateCommand ( const geometry_msgs::Twist start,
const geometry_msgs::Twist end,
const geometry_msgs::Twist max_rate,
const double &  dT 
) [private]

interpolates velocities within a given time based on maximum accelerations

Definition at line 214 of file pr2_base_controller.cpp.

void controller::Pr2BaseController::publishState ( const ros::Time current_time  )  [private]

Publish the state.

Definition at line 317 of file pr2_base_controller.cpp.

void controller::Pr2BaseController::setCommand ( const geometry_msgs::Twist cmd_vel  ) 

Definition at line 181 of file pr2_base_controller.cpp.

void controller::Pr2BaseController::setDesiredCasterSteer (  ) 

set the desired caster steer

Definition at line 414 of file pr2_base_controller.cpp.

void controller::Pr2BaseController::setDesiredWheelSpeeds (  )  [private]

sends the desired wheel speeds to the wheel controllers

Definition at line 451 of file pr2_base_controller.cpp.

void controller::Pr2BaseController::setJointCommands (  ) 

set the joint commands

Definition at line 366 of file pr2_base_controller.cpp.

void controller::Pr2BaseController::starting (  )  [virtual]

Reimplemented from pr2_controller_interface::Controller.

Definition at line 264 of file pr2_base_controller.cpp.

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

(a) Updates commands to caster and wheels. Called every timestep in realtime

Implements pr2_controller_interface::Controller.

Definition at line 278 of file pr2_base_controller.cpp.

void controller::Pr2BaseController::updateJointControllers (  )  [private]

tells the wheel and caster controllers to update their speeds

Definition at line 459 of file pr2_base_controller.cpp.


Member Data Documentation

low pass filter value used for finding stalls

Definition at line 192 of file pr2_base_controller.h.

class where the robot's information is computed and stored

Returns:
BaseKinematic instance that is being used by this controller

Definition at line 95 of file pr2_base_controller.h.

callback message, used to remember where the base is commanded to go

Definition at line 247 of file pr2_base_controller.h.

vector that stores the caster controllers

Definition at line 202 of file pr2_base_controller.h.

The pid controllers for caster position.

Definition at line 285 of file pr2_base_controller.h.

Definition at line 287 of file pr2_base_controller.h.

timestamp corresponding to when the command received by the node

Definition at line 146 of file pr2_base_controller.h.

Definition at line 124 of file pr2_base_controller.h.

Definition at line 126 of file pr2_base_controller.h.

speed command vector used internally to represent the current commanded speed

Definition at line 157 of file pr2_base_controller.h.

minimum rotational velocity value allowable

Definition at line 257 of file pr2_base_controller.h.

Input speed command vector represents the desired speed requested by the node. Note that this may differ from the current commanded speed due to acceleration limits imposed by the controller.

Definition at line 152 of file pr2_base_controller.h.

minimum tranlational velocity value allowable

Definition at line 272 of file pr2_base_controller.h.

Input speed command vector represents the desired speed requested by the node.

Definition at line 162 of file pr2_base_controller.h.

generic epsilon value that is used as a minimum or maximum allowable input value

Definition at line 252 of file pr2_base_controller.h.

Definition at line 289 of file pr2_base_controller.h.

local gain used for speed control of the caster (to achieve resultant position control)

Definition at line 187 of file pr2_base_controller.h.

Time interval between state publishing.

Definition at line 267 of file pr2_base_controller.h.

time corresponding to when update was last called

Definition at line 141 of file pr2_base_controller.h.

acceleration limits specified externally

Definition at line 172 of file pr2_base_controller.h.

maximum rotational velocity magnitude allowable

Definition at line 182 of file pr2_base_controller.h.

maximum translational velocity magnitude allowable

Definition at line 177 of file pr2_base_controller.h.

velocity limits specified externally

Definition at line 167 of file pr2_base_controller.h.

true when new command received by node

Definition at line 136 of file pr2_base_controller.h.

Definition at line 120 of file pr2_base_controller.h.

mutex lock for setting and getting commands

Definition at line 100 of file pr2_base_controller.h.

Definition at line 280 of file pr2_base_controller.h.

Definition at line 122 of file pr2_base_controller.h.

Definition at line 262 of file pr2_base_controller.h.

Time interval between state publishing.

Definition at line 262 of file pr2_base_controller.h.

publishes information about the caster and wheel controllers

Definition at line 207 of file pr2_base_controller.h.

timeout specifying time that the controller waits before setting the current velocity command to zero

Definition at line 131 of file pr2_base_controller.h.

vector that stores the wheel controllers

Definition at line 197 of file pr2_base_controller.h.


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


pr2_mechanism_controllers
Author(s): Sachin Chita, John Hsu, Melonee Wise
autogenerated on Fri Mar 1 16:53:00 2013