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