55 #ifndef CASTER_CONTROLLER_H 56 #define CASTER_CONTROLLER_H 64 #include "std_msgs/Float64.h" 65 #include <boost/thread/condition.hpp> 79 const std::string &caster_joint,
80 const std::string &wheel_l_joint,
const std::string &wheel_r_joint,
100 void setSteerCB(
const std_msgs::Float64ConstPtr& msg);
101 void setDriveCB(
const std_msgs::Float64ConstPtr& msg);
static const double WHEEL_OFFSET
JointVelocityController caster_vel_
pr2_mechanism_model::JointState * caster_
JointVelocityController wheel_r_vel_
void setSteerCB(const std_msgs::Float64ConstPtr &msg)
JointVelocityController wheel_l_vel_
void setDriveCB(const std_msgs::Float64ConstPtr &msg)
double getSteerPosition()
ros::Subscriber steer_cmd_
ros::Subscriber drive_cmd_
bool init(pr2_mechanism_model::RobotState *robot_state, const std::string &caster_joint, const std::string &wheel_l_joint, const std::string &wheel_r_joint, const control_toolbox::Pid &caster_pid, const control_toolbox::Pid &wheel_pid)
double getSteerVelocity()
static const double WHEEL_RADIUS