#include <pr2_base_controller2.h>

Public Member Functions | |
| geometry_msgs::Twist | getCommand () |
| Returns the current position command. More... | |
| bool | init (pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n) |
| Pr2BaseController2 () | |
| Default Constructor of the Pr2BaseController2 class. More... | |
| void | setCommand (const geometry_msgs::Twist &cmd_vel) |
| void | setDesiredCasterSteer () |
| set the desired caster steer More... | |
| void | setJointCommands () |
| set the joint commands More... | |
| void | starting () |
| void | update () |
| (a) Updates commands to caster and wheels. Called every timestep in realtime More... | |
| ~Pr2BaseController2 () | |
| Destructor of the Pr2BaseController2 class. More... | |
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) |
| 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 | |
| BaseKinematics | base_kinematics_ |
| class where the robot's information is computed and stored More... | |
| pthread_mutex_t | pr2_base_controller_lock_ |
| mutex lock for setting and getting commands More... | |
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_ |
Private Member Functions | |
| void | commandCallback (const geometry_msgs::TwistConstPtr &msg) |
| deal with Twist commands More... | |
| void | computeDesiredCasterSteer (const double &dT) |
| computes the desired caster speeds given the desired base speed More... | |
| void | computeDesiredWheelSpeeds (const double &dT) |
| computes the desired wheel speeds given the desired base speed More... | |
| void | computeJointCommands (const double &dT) |
| computes the desired caster steers and wheel speeds More... | |
| 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 More... | |
| void | publishState (const ros::Time ¤t_time) |
| Publish the state. More... | |
| void | setDesiredWheelSpeeds () |
| sends the desired wheel speeds to the wheel controllers More... | |
| void | updateJointControllers () |
| tells the wheel and caster controllers to update their speeds More... | |
Private Attributes | |
| double | alpha_stall_ |
| low pass filter value used for finding stalls More... | |
| geometry_msgs::Twist | base_vel_msg_ |
| callback message, used to remember where the base is commanded to go More... | |
| std::vector< boost::shared_ptr< JointVelocityController > > | caster_controller_ |
| vector that stores the caster controllers More... | |
| std::vector< control_toolbox::Pid > | caster_position_pid_ |
| The pid controllers for caster position. More... | |
| filters::MultiChannelTransferFunctionFilter< double > | caster_vel_filter_ |
| ros::Time | cmd_received_timestamp_ |
| timestamp corresponding to when the command received by the node More... | |
| 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 More... | |
| double | cmd_vel_rot_eps_ |
| minimum rotational velocity value allowable More... | |
| 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. More... | |
| double | cmd_vel_trans_eps_ |
| minimum tranlational velocity value allowable More... | |
| geometry_msgs::Twist | desired_vel_ |
| Input speed command vector represents the desired speed requested by the node. More... | |
| double | eps_ |
| generic epsilon value that is used as a minimum or maximum allowable input value More... | |
| 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) More... | |
| ros::Time | last_publish_time_ |
| Time interval between state publishing. More... | |
| ros::Time | last_time_ |
| time corresponding to when update was last called More... | |
| geometry_msgs::Twist | max_accel_ |
| acceleration limits specified externally More... | |
| double | max_rotational_velocity_ |
| maximum rotational velocity magnitude allowable More... | |
| double | max_translational_velocity_ |
| maximum translational velocity magnitude allowable More... | |
| geometry_msgs::Twist | max_vel_ |
| velocity limits specified externally More... | |
| bool | new_cmd_available_ |
| true when new command received by node More... | |
| ros::NodeHandle | node_ |
| bool | publish_state_ |
| ros::NodeHandle | root_handle_ |
| double | state_publish_rate_ |
| double | state_publish_time_ |
| Time interval between state publishing. More... | |
| boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_mechanism_controllers::BaseControllerState2 > > | state_publisher_ |
| publishes information about the caster and wheel controllers More... | |
| double | timeout_ |
| timeout specifying time that the controller waits before setting the current velocity command to zero More... | |
| std::vector< boost::shared_ptr< JointVelocityController > > | wheel_controller_ |
| vector that stores the wheel controllers More... | |
| std::vector< control_toolbox::Pid > | wheel_pid_controllers_ |
| The pid controllers for caster position. More... | |
| filters::MultiChannelTransferFunctionFilter< double > | wheel_vel_filter_ |
Definition at line 54 of file pr2_base_controller2.h.
| controller::Pr2BaseController2::Pr2BaseController2 | ( | ) |
Default Constructor of the Pr2BaseController2 class.
Definition at line 47 of file pr2_base_controller2.cpp.
| controller::Pr2BaseController2::~Pr2BaseController2 | ( | ) |
Destructor of the Pr2BaseController2 class.
Definition at line 68 of file pr2_base_controller2.cpp.
|
private |
deal with Twist commands
Definition at line 494 of file pr2_base_controller2.cpp.
|
private |
computes the desired caster speeds given the desired base speed
Definition at line 381 of file pr2_base_controller2.cpp.
|
private |
computes the desired wheel speeds given the desired base speed
Definition at line 437 of file pr2_base_controller2.cpp.
|
private |
computes the desired caster steers and wheel speeds
Definition at line 365 of file pr2_base_controller2.cpp.
| geometry_msgs::Twist controller::Pr2BaseController2::getCommand | ( | ) |
Returns the current position command.
Definition at line 260 of file pr2_base_controller2.cpp.
|
virtual |
Implements pr2_controller_interface::Controller.
Definition at line 74 of file pr2_base_controller2.cpp.
|
private |
interpolates velocities within a given time based on maximum accelerations
Definition at line 221 of file pr2_base_controller2.cpp.
|
private |
Publish the state.
Definition at line 324 of file pr2_base_controller2.cpp.
| void controller::Pr2BaseController2::setCommand | ( | const geometry_msgs::Twist & | cmd_vel | ) |
Definition at line 188 of file pr2_base_controller2.cpp.
| void controller::Pr2BaseController2::setDesiredCasterSteer | ( | ) |
set the desired caster steer
Definition at line 429 of file pr2_base_controller2.cpp.
|
private |
sends the desired wheel speeds to the wheel controllers
Definition at line 478 of file pr2_base_controller2.cpp.
| void controller::Pr2BaseController2::setJointCommands | ( | ) |
set the joint commands
Definition at line 374 of file pr2_base_controller2.cpp.
|
virtual |
Reimplemented from pr2_controller_interface::Controller.
Definition at line 271 of file pr2_base_controller2.cpp.
|
virtual |
(a) Updates commands to caster and wheels. Called every timestep in realtime
Implements pr2_controller_interface::Controller.
Definition at line 285 of file pr2_base_controller2.cpp.
|
private |
tells the wheel and caster controllers to update their speeds
Definition at line 486 of file pr2_base_controller2.cpp.
|
private |
low pass filter value used for finding stalls
Definition at line 191 of file pr2_base_controller2.h.
| BaseKinematics controller::Pr2BaseController2::base_kinematics_ |
class where the robot's information is computed and stored
Definition at line 94 of file pr2_base_controller2.h.
|
private |
callback message, used to remember where the base is commanded to go
Definition at line 246 of file pr2_base_controller2.h.
|
private |
vector that stores the caster controllers
Definition at line 201 of file pr2_base_controller2.h.
|
private |
The pid controllers for caster position.
Definition at line 284 of file pr2_base_controller2.h.
|
private |
Definition at line 286 of file pr2_base_controller2.h.
|
private |
timestamp corresponding to when the command received by the node
Definition at line 145 of file pr2_base_controller2.h.
|
private |
Definition at line 123 of file pr2_base_controller2.h.
|
private |
Definition at line 125 of file pr2_base_controller2.h.
|
private |
speed command vector used internally to represent the current commanded speed
Definition at line 156 of file pr2_base_controller2.h.
|
private |
minimum rotational velocity value allowable
Definition at line 256 of file pr2_base_controller2.h.
|
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 151 of file pr2_base_controller2.h.
|
private |
minimum tranlational velocity value allowable
Definition at line 271 of file pr2_base_controller2.h.
|
private |
Input speed command vector represents the desired speed requested by the node.
Definition at line 161 of file pr2_base_controller2.h.
|
private |
generic epsilon value that is used as a minimum or maximum allowable input value
Definition at line 251 of file pr2_base_controller2.h.
|
private |
Definition at line 288 of file pr2_base_controller2.h.
|
private |
Definition at line 292 of file pr2_base_controller2.h.
|
private |
local gain used for speed control of the caster (to achieve resultant position control)
Definition at line 186 of file pr2_base_controller2.h.
|
private |
Time interval between state publishing.
Definition at line 266 of file pr2_base_controller2.h.
|
private |
time corresponding to when update was last called
Definition at line 140 of file pr2_base_controller2.h.
|
private |
acceleration limits specified externally
Definition at line 171 of file pr2_base_controller2.h.
|
private |
maximum rotational velocity magnitude allowable
Definition at line 181 of file pr2_base_controller2.h.
|
private |
maximum translational velocity magnitude allowable
Definition at line 176 of file pr2_base_controller2.h.
|
private |
velocity limits specified externally
Definition at line 166 of file pr2_base_controller2.h.
|
private |
true when new command received by node
Definition at line 135 of file pr2_base_controller2.h.
|
private |
Definition at line 119 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 99 of file pr2_base_controller2.h.
|
private |
Definition at line 279 of file pr2_base_controller2.h.
|
private |
Definition at line 121 of file pr2_base_controller2.h.
|
private |
Definition at line 261 of file pr2_base_controller2.h.
|
private |
Time interval between state publishing.
Definition at line 261 of file pr2_base_controller2.h.
|
private |
publishes information about the caster and wheel controllers
Definition at line 206 of file pr2_base_controller2.h.
|
private |
timeout specifying time that the controller waits before setting the current velocity command to zero
Definition at line 130 of file pr2_base_controller2.h.
|
private |
vector that stores the wheel controllers
Definition at line 196 of file pr2_base_controller2.h.
|
private |
The pid controllers for caster position.
Definition at line 297 of file pr2_base_controller2.h.
|
private |
Definition at line 290 of file pr2_base_controller2.h.