45 JointLimitCalibrationController::JointLimitCalibrationController()
46 : robot_(NULL), last_publish_time_(0), state_(INITIALIZED),
47 count_(0), stop_count_(0), search_velocity_(0),
48 actuator_(NULL), joint_(NULL), transmission_(NULL)
52 JointLimitCalibrationController::~JointLimitCalibrationController()
63 std::string joint_name;
71 ROS_ERROR(
"Could not find joint %s (namespace: %s)",
77 std::string actuator_name;
85 ROS_ERROR(
"Could not find actuator %s (namespace: %s)",
91 std::string transmission_name;
99 ROS_ERROR(
"Could not find transmission %s (namespace: %s)",
157 std::vector<pr2_hardware_interface::Actuator*> fake_a;
158 std::vector<pr2_mechanism_model::JointState*> fake_j;
159 fake_a.push_back(&a);
160 fake_j.push_back(&j);
167 double ref_position = 0;
174 fake_j[0]->position_ = fake_j[0]->position_ - ref_position;
boost::scoped_ptr< realtime_tools::RealtimePublisher< std_msgs::Empty > > pub_calibrated_
PLUGINLIB_EXPORT_CLASS(joint_qualification_controllers::JointLimitCalibrationController, pr2_controller_interface::Controller) JointLimitCalibrationController
pr2_mechanism_model::RobotState * robot_
boost::shared_ptr< pr2_mechanism_model::Transmission > getTransmission(const std::string &name) const
pr2_mechanism_model::JointState * joint_
virtual bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
ros::Time last_publish_time_
boost::shared_ptr< const urdf::Joint > joint_
pr2_mechanism_model::Transmission * transmission_
virtual void propagatePosition(std::vector< pr2_hardware_interface::Actuator * > &, std::vector< pr2_mechanism_model::JointState * > &)=0
pr2_hardware_interface::Actuator * getActuator(const std::string &name) const
void setCommand(double cmd)
bool getParam(const std::string &key, std::string &s) const
controller::JointVelocityController vc_
JointState * getJointState(const std::string &name)
const std::string & getNamespace() const
pr2_hardware_interface::Actuator * actuator_
bool init(pr2_mechanism_model::RobotState *robot, const std::string &joint_name, const control_toolbox::Pid &pid)
virtual void propagatePositionBackwards(std::vector< pr2_mechanism_model::JointState * > &, std::vector< pr2_hardware_interface::Actuator * > &)=0