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;
64 if (!node_.getParam(
"joint", joint_name))
66 ROS_ERROR(
"No joint given (namespace: %s)", node_.getNamespace().c_str());
71 ROS_ERROR(
"Could not find joint %s (namespace: %s)",
72 joint_name.c_str(), node_.getNamespace().c_str());
77 std::string actuator_name;
78 if (!node_.getParam(
"actuator", actuator_name))
80 ROS_ERROR(
"No actuator given (namespace: %s)", node_.getNamespace().c_str());
85 ROS_ERROR(
"Could not find actuator %s (namespace: %s)",
86 actuator_name.c_str(), node_.getNamespace().c_str());
91 std::string transmission_name;
92 if (!node_.getParam(
"transmission", transmission_name))
94 ROS_ERROR(
"No transmission given (namespace: %s)", node_.getNamespace().c_str());
99 ROS_ERROR(
"Could not find transmission %s (namespace: %s)",
100 transmission_name.c_str(), node_.getNamespace().c_str());
104 if (!node_.getParam(
"velocity", search_velocity_))
106 ROS_ERROR(
"Velocity value was not specified (namespace: %s)", node_.getNamespace().c_str());
111 if (!vc_.init(robot, node_))
115 pub_calibrated_.reset(
121 void JointLimitCalibrationController::update()
133 joint_->calibrated_ =
false;
134 actuator_->state_.zero_offset_ = 0.0;
135 vc_.setCommand(search_velocity_);
147 if (fabs(joint_->velocity_) < 0.001)
152 if (stop_count_ > 250)
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);
162 fake_a[0]->state_.
position_ = actuator_->state_.position_;
164 transmission_->propagatePosition(fake_a, fake_j);
167 double ref_position = 0;
168 if (search_velocity_ < 0)
169 ref_position = joint_->joint_->limits->lower;
171 ref_position = joint_->joint_->limits->upper;
174 fake_j[0]->position_ = fake_j[0]->position_ - ref_position;
176 transmission_->propagatePositionBackwards(fake_j, fake_a);
178 actuator_->state_.zero_offset_ = fake_a[0]->state_.position_;
180 joint_->calibrated_ =
true;
187 if (last_publish_time_ +
ros::Duration(0.5) < robot_->getTime())
189 if (pub_calibrated_->trylock())
191 last_publish_time_ = robot_->getTime();
192 pub_calibrated_->unlockAndPublish();
199 if (state_ != CALIBRATED)
boost::shared_ptr< pr2_mechanism_model::Transmission > getTransmission(const std::string &name) const
PLUGINLIB_EXPORT_CLASS(joint_qualification_controllers::JointLimitCalibrationController, pr2_controller_interface::Controller) JointLimitCalibrationController
JointState * getJointState(const std::string &name)
pr2_hardware_interface::Actuator * getActuator(const std::string &name) const