#include <pr2_base_controller2.h>
| Public Member Functions | |
| geometry_msgs::Twist | getCommand () | 
| Returns the current position command. | |
| bool | init (pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n) | 
| Pr2BaseController2 () | |
| Default Constructor of the Pr2BaseController2 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 | |
| ~Pr2BaseController2 () | |
| Destructor of the Pr2BaseController2 class. | |
| Public Attributes | |
| BaseKinematics | base_kinematics_ | 
| 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 (const double &dT) | 
| 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 ¤t_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::Pid > | caster_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_ | 
| std::vector< double > | filtered_wheel_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::BaseControllerState2 > > | 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 | |
| std::vector< control_toolbox::Pid > | wheel_pid_controllers_ | 
| The pid controllers for caster position. | |
| filters::MultiChannelTransferFunctionFilter < double > | wheel_vel_filter_ | 
Definition at line 45 of file pr2_base_controller2.h.
| controller::Pr2BaseController2::Pr2BaseController2 | ( | ) | 
Default Constructor of the Pr2BaseController2 class.
Definition at line 43 of file pr2_base_controller2.cpp.
| controller::Pr2BaseController2::~Pr2BaseController2 | ( | ) | 
Destructor of the Pr2BaseController2 class.
Definition at line 64 of file pr2_base_controller2.cpp.
| void controller::Pr2BaseController2::commandCallback | ( | const geometry_msgs::TwistConstPtr & | msg | ) |  [private] | 
deal with Twist commands
Definition at line 484 of file pr2_base_controller2.cpp.
| void controller::Pr2BaseController2::computeDesiredCasterSteer | ( | const double & | dT | ) |  [private] | 
computes the desired caster speeds given the desired base speed
Definition at line 377 of file pr2_base_controller2.cpp.
| void controller::Pr2BaseController2::computeDesiredWheelSpeeds | ( | const double & | dT | ) |  [private] | 
computes the desired wheel speeds given the desired base speed
Definition at line 430 of file pr2_base_controller2.cpp.
| void controller::Pr2BaseController2::computeJointCommands | ( | const double & | dT | ) |  [private] | 
computes the desired caster steers and wheel speeds
Definition at line 361 of file pr2_base_controller2.cpp.
| geometry_msgs::Twist controller::Pr2BaseController2::getCommand | ( | ) | 
Returns the current position command.
Definition at line 256 of file pr2_base_controller2.cpp.
| bool controller::Pr2BaseController2::init | ( | pr2_mechanism_model::RobotState * | robot, | |
| ros::NodeHandle & | n | |||
| ) | 
Definition at line 70 of file pr2_base_controller2.cpp.
| geometry_msgs::Twist controller::Pr2BaseController2::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 217 of file pr2_base_controller2.cpp.
| void controller::Pr2BaseController2::publishState | ( | const ros::Time & | current_time | ) |  [private] | 
Publish the state.
Definition at line 320 of file pr2_base_controller2.cpp.
| void controller::Pr2BaseController2::setCommand | ( | const geometry_msgs::Twist & | cmd_vel | ) | 
Definition at line 184 of file pr2_base_controller2.cpp.
| void controller::Pr2BaseController2::setDesiredCasterSteer | ( | ) | 
set the desired caster steer
Definition at line 422 of file pr2_base_controller2.cpp.
| void controller::Pr2BaseController2::setDesiredWheelSpeeds | ( | ) |  [private] | 
sends the desired wheel speeds to the wheel controllers
Definition at line 468 of file pr2_base_controller2.cpp.
| void controller::Pr2BaseController2::setJointCommands | ( | ) | 
set the joint commands
Definition at line 370 of file pr2_base_controller2.cpp.
| void controller::Pr2BaseController2::starting | ( | ) | 
Definition at line 267 of file pr2_base_controller2.cpp.
| void controller::Pr2BaseController2::update | ( | ) | 
(a) Updates commands to caster and wheels. Called every timestep in realtime
Definition at line 281 of file pr2_base_controller2.cpp.
| void controller::Pr2BaseController2::updateJointControllers | ( | ) |  [private] | 
tells the wheel and caster controllers to update their speeds
Definition at line 476 of file pr2_base_controller2.cpp.
| double controller::Pr2BaseController2::alpha_stall_  [private] | 
low pass filter value used for finding stalls
Definition at line 182 of file pr2_base_controller2.h.
class where the robot's information is computed and stored
Definition at line 85 of file pr2_base_controller2.h.
| geometry_msgs::Twist controller::Pr2BaseController2::base_vel_msg_  [private] | 
callback message, used to remember where the base is commanded to go
Definition at line 237 of file pr2_base_controller2.h.
| std::vector<boost::shared_ptr<JointVelocityController> > controller::Pr2BaseController2::caster_controller_  [private] | 
vector that stores the caster controllers
Definition at line 192 of file pr2_base_controller2.h.
| std::vector<control_toolbox::Pid> controller::Pr2BaseController2::caster_position_pid_  [private] | 
The pid controllers for caster position.
Definition at line 275 of file pr2_base_controller2.h.
| filters::MultiChannelTransferFunctionFilter<double> controller::Pr2BaseController2::caster_vel_filter_  [private] | 
Definition at line 277 of file pr2_base_controller2.h.
| ros::Time controller::Pr2BaseController2::cmd_received_timestamp_  [private] | 
timestamp corresponding to when the command received by the node
Definition at line 136 of file pr2_base_controller2.h.
| ros::Subscriber controller::Pr2BaseController2::cmd_sub_  [private] | 
Definition at line 114 of file pr2_base_controller2.h.
| ros::Subscriber controller::Pr2BaseController2::cmd_sub_deprecated_  [private] | 
Definition at line 116 of file pr2_base_controller2.h.
| geometry_msgs::Twist controller::Pr2BaseController2::cmd_vel_  [private] | 
speed command vector used internally to represent the current commanded speed
Definition at line 147 of file pr2_base_controller2.h.
| double controller::Pr2BaseController2::cmd_vel_rot_eps_  [private] | 
minimum rotational velocity value allowable
Definition at line 247 of file pr2_base_controller2.h.
| geometry_msgs::Twist controller::Pr2BaseController2::cmd_vel_t_  [private] | 
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 142 of file pr2_base_controller2.h.
| double controller::Pr2BaseController2::cmd_vel_trans_eps_  [private] | 
minimum tranlational velocity value allowable
Definition at line 262 of file pr2_base_controller2.h.
| geometry_msgs::Twist controller::Pr2BaseController2::desired_vel_  [private] | 
Input speed command vector represents the desired speed requested by the node.
Definition at line 152 of file pr2_base_controller2.h.
| double controller::Pr2BaseController2::eps_  [private] | 
generic epsilon value that is used as a minimum or maximum allowable input value
Definition at line 242 of file pr2_base_controller2.h.
| std::vector<double> controller::Pr2BaseController2::filtered_velocity_  [private] | 
Definition at line 279 of file pr2_base_controller2.h.
| std::vector<double> controller::Pr2BaseController2::filtered_wheel_velocity_  [private] | 
Definition at line 283 of file pr2_base_controller2.h.
| double controller::Pr2BaseController2::kp_caster_steer_  [private] | 
local gain used for speed control of the caster (to achieve resultant position control)
Definition at line 177 of file pr2_base_controller2.h.
| ros::Time controller::Pr2BaseController2::last_publish_time_  [private] | 
Time interval between state publishing.
Definition at line 257 of file pr2_base_controller2.h.
| ros::Time controller::Pr2BaseController2::last_time_  [private] | 
time corresponding to when update was last called
Definition at line 131 of file pr2_base_controller2.h.
| geometry_msgs::Twist controller::Pr2BaseController2::max_accel_  [private] | 
acceleration limits specified externally
Definition at line 162 of file pr2_base_controller2.h.
| double controller::Pr2BaseController2::max_rotational_velocity_  [private] | 
maximum rotational velocity magnitude allowable
Definition at line 172 of file pr2_base_controller2.h.
| double controller::Pr2BaseController2::max_translational_velocity_  [private] | 
maximum translational velocity magnitude allowable
Definition at line 167 of file pr2_base_controller2.h.
| geometry_msgs::Twist controller::Pr2BaseController2::max_vel_  [private] | 
velocity limits specified externally
Definition at line 157 of file pr2_base_controller2.h.
| bool controller::Pr2BaseController2::new_cmd_available_  [private] | 
true when new command received by node
Definition at line 126 of file pr2_base_controller2.h.
| ros::NodeHandle controller::Pr2BaseController2::node_  [private] | 
Definition at line 110 of file pr2_base_controller2.h.
| pthread_mutex_t controller::Pr2BaseController2::pr2_base_controller_lock_ | 
mutex lock for setting and getting commands
Definition at line 90 of file pr2_base_controller2.h.
| bool controller::Pr2BaseController2::publish_state_  [private] | 
Definition at line 270 of file pr2_base_controller2.h.
| ros::NodeHandle controller::Pr2BaseController2::root_handle_  [private] | 
Definition at line 112 of file pr2_base_controller2.h.
| double controller::Pr2BaseController2::state_publish_rate_  [private] | 
Definition at line 252 of file pr2_base_controller2.h.
| double controller::Pr2BaseController2::state_publish_time_  [private] | 
Time interval between state publishing.
Definition at line 252 of file pr2_base_controller2.h.
| boost::scoped_ptr<realtime_tools::RealtimePublisher<pr2_mechanism_controllers::BaseControllerState2> > controller::Pr2BaseController2::state_publisher_  [private] | 
publishes information about the caster and wheel controllers
Definition at line 197 of file pr2_base_controller2.h.
| double controller::Pr2BaseController2::timeout_  [private] | 
timeout specifying time that the controller waits before setting the current velocity command to zero
Definition at line 121 of file pr2_base_controller2.h.
| std::vector<boost::shared_ptr<JointVelocityController> > controller::Pr2BaseController2::wheel_controller_  [private] | 
vector that stores the wheel controllers
Definition at line 187 of file pr2_base_controller2.h.
| std::vector<control_toolbox::Pid> controller::Pr2BaseController2::wheel_pid_controllers_  [private] | 
The pid controllers for caster position.
Definition at line 288 of file pr2_base_controller2.h.
| filters::MultiChannelTransferFunctionFilter<double> controller::Pr2BaseController2::wheel_vel_filter_  [private] | 
Definition at line 281 of file pr2_base_controller2.h.