40 #include <pr2_mechanism_controllers/BaseControllerState.h> 43 #include <geometry_msgs/Twist.h> 45 #include <boost/shared_ptr.hpp> 46 #include <boost/scoped_ptr.hpp> 47 #include <boost/thread/condition.hpp> 83 void setCommand(
const geometry_msgs::Twist &cmd_vel);
207 boost::scoped_ptr<realtime_tools::RealtimePublisher<pr2_mechanism_controllers::BaseControllerState> >
state_publisher_;
237 geometry_msgs::Twist
interpolateCommand(
const geometry_msgs::Twist &start,
const geometry_msgs::Twist &end,
const geometry_msgs::Twist &max_rate,
const double &dT);
void setJointCommands()
set the joint commands
ros::Time cmd_received_timestamp_
timestamp corresponding to when the command received by the node
void computeJointCommands(const double &dT)
computes the desired caster steers and wheel speeds
bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
void commandCallback(const geometry_msgs::TwistConstPtr &msg)
deal with Twist commands
std::vector< control_toolbox::Pid > caster_position_pid_
The pid controllers for caster position.
geometry_msgs::Twist base_vel_msg_
callback message, used to remember where the base is commanded to go
double eps_
generic epsilon value that is used as a minimum or maximum allowable input value
void updateJointControllers()
tells the wheel and caster controllers to update their speeds
geometry_msgs::Twist max_vel_
velocity limits specified externally
double max_translational_velocity_
maximum translational velocity magnitude allowable
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_mechanism_controllers::BaseControllerState > > state_publisher_
publishes information about the caster and wheel controllers
geometry_msgs::Twist cmd_vel_t_
Input speed command vector represents the desired speed requested by the node. Note that this may dif...
geometry_msgs::Twist desired_vel_
Input speed command vector represents the desired speed requested by the node.
double cmd_vel_rot_eps_
minimum rotational velocity value allowable
Pr2BaseController()
Default Constructor of the Pr2BaseController class.
double state_publish_rate_
bool new_cmd_available_
true when new command received by node
void update()
(a) Updates commands to caster and wheels. Called every timestep in realtime
ros::Time last_time_
time corresponding to when update was last called
filters::MultiChannelTransferFunctionFilter< double > caster_vel_filter_
double cmd_vel_trans_eps_
minimum tranlational velocity value allowable
double timeout_
timeout specifying time that the controller waits before setting the current velocity command to zero...
void publishState(const ros::Time ¤t_time)
Publish the state.
double kp_caster_steer_
local gain used for speed control of the caster (to achieve resultant position control) ...
void setCommand(const geometry_msgs::Twist &cmd_vel)
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
geometry_msgs::Twist max_accel_
acceleration limits specified externally
double alpha_stall_
low pass filter value used for finding stalls
pthread_mutex_t pr2_base_controller_lock_
mutex lock for setting and getting commands
geometry_msgs::Twist cmd_vel_
speed command vector used internally to represent the current commanded speed
~Pr2BaseController()
Destructor of the Pr2BaseController class.
ros::Subscriber cmd_sub_deprecated_
std::vector< boost::shared_ptr< JointVelocityController > > caster_controller_
vector that stores the caster controllers
double state_publish_time_
Time interval between state publishing.
double max_rotational_velocity_
maximum rotational velocity magnitude allowable
void setDesiredCasterSteer()
set the desired caster steer
ros::NodeHandle root_handle_
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
BaseKinematics base_kin_
class where the robot's information is computed and stored
geometry_msgs::Twist getCommand()
Returns the current position command.
std::vector< double > filtered_velocity_
ros::Time last_publish_time_
Time interval between state publishing.
std::vector< boost::shared_ptr< JointVelocityController > > wheel_controller_
vector that stores the wheel controllers
void setDesiredWheelSpeeds()
sends the desired wheel speeds to the wheel controllers