41 const double CasterController::WHEEL_RADIUS = 0.079;
42 const double CasterController::WHEEL_OFFSET = 0.049;
44 CasterController::CasterController()
45 : steer_velocity_(0), drive_velocity_(0)
55 const std::string &caster_joint,
56 const std::string &wheel_l_joint,
const std::string &wheel_r_joint,
62 fprintf(stderr,
"Error: Caster joint \"%s\" does not exist\n", caster_joint.c_str());
83 std::string caster_joint_name, wheel_l_joint_name, wheel_r_joint_name;
101 ROS_ERROR(
"Caster joint \"%s\" does not exist (namespace: %s)",
113 caster_node(n,
"caster"),
114 wheel_l_node(n,
"wheel_l"),
115 wheel_r_node(n,
"wheel_r");
117 caster_node.setParam(
"type", std::string(
"JointVelocityController"));
118 caster_node.setParam(
"joint", caster_joint_name);
119 caster_node.setParam(
"pid", caster_pid);
121 wheel_l_node.setParam(
"type", std::string(
"JointVelocityController"));
122 wheel_l_node.setParam(
"joint", wheel_l_joint_name);
123 wheel_l_node.setParam(
"pid", wheel_pid);
125 wheel_r_node.
setParam(
"type", std::string(
"JointVelocityController"));
126 wheel_r_node.
setParam(
"joint", wheel_r_joint_name);
127 wheel_r_node.
setParam(
"pid", wheel_pid);
PLUGINLIB_EXPORT_CLASS(my_controller_ns::MyControllerClass, pr2_controller_interface::Controller)
static const double WHEEL_OFFSET
JointVelocityController caster_vel_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
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)
void setCommand(double cmd)
const std::string & getNamespace() const
ros::Subscriber steer_cmd_
JointState * getJointState(const std::string &name)
ros::Subscriber drive_cmd_
bool getParam(const std::string &key, std::string &s) const
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)
static const double WHEEL_RADIUS
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
bool init(pr2_mechanism_model::RobotState *robot, const std::string &joint_name, const control_toolbox::Pid &pid)