Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Improve joint calibration controller #406

Open
wants to merge 2 commits into
base: melodic-devel
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,7 @@
#include "robot_mechanism_controllers/joint_velocity_controller.h"
#include "realtime_tools/realtime_publisher.h"
#include "std_msgs/Empty.h"
#include "std_msgs/Float32.h"
#include "pr2_controllers_msgs/QueryCalibrationState.h"


Expand All @@ -65,13 +66,15 @@ class JointCalibrationController : public pr2_controller_interface::Controller
protected:
pr2_mechanism_model::RobotState* robot_;
ros::NodeHandle node_;
ros::Time last_publish_time_;
ros::ServiceServer is_calibrated_srv_;
boost::scoped_ptr<realtime_tools::RealtimePublisher<std_msgs::Empty> > pub_calibrated_;
boost::scoped_ptr<realtime_tools::RealtimePublisher<std_msgs::Float32> > pub_zero_offset_;

enum { INITIALIZED, BEGINNING, MOVING_TO_LOW, MOVING_TO_HIGH, CALIBRATED };
int state_;
bool announced_calibration_success_;
int countdown_;
int tics_moving_past_calibration_reading_;

double search_velocity_;
double original_position_;
Expand Down
32 changes: 20 additions & 12 deletions pr2_calibration_controllers/src/joint_calibration_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,8 +43,7 @@ using namespace std;
namespace controller {

JointCalibrationController::JointCalibrationController()
: robot_(NULL), last_publish_time_(0),
actuator_(NULL), joint_(NULL)
: robot_(NULL), actuator_(NULL), joint_(NULL)
{
}

Expand Down Expand Up @@ -91,11 +90,15 @@ bool JointCalibrationController::init(pr2_mechanism_model::RobotState *robot, ro
return false;
}

tics_moving_past_calibration_reading_ = 200;
node_.getParam("tics_moving_past_calibration_reading", tics_moving_past_calibration_reading_);

bool force_calibration = false;
node_.getParam("force_calibration", force_calibration);

state_ = INITIALIZED;
joint_->calibrated_ = false;
announced_calibration_success_ = false;
if (actuator_->state_.zero_offset_ != 0)
{
if (force_calibration)
Expand Down Expand Up @@ -173,8 +176,8 @@ bool JointCalibrationController::init(pr2_mechanism_model::RobotState *robot, ro
is_calibrated_srv_ = node_.advertiseService("is_calibrated", &JointCalibrationController::isCalibrated, this);

// "Calibrated" topic
pub_calibrated_.reset(new realtime_tools::RealtimePublisher<std_msgs::Empty>(node_, "calibrated", 1));

pub_calibrated_.reset(new realtime_tools::RealtimePublisher<std_msgs::Empty>(node_, "calibrated", 1, true));
pub_zero_offset_.reset(new realtime_tools::RealtimePublisher<std_msgs::Float32>(node_, "zero_offset", 1, true));

return true;
}
Expand All @@ -185,6 +188,7 @@ void JointCalibrationController::starting()
state_ = INITIALIZED;
joint_->calibrated_ = false;
actuator_->state_.zero_offset_ = 0.0;
announced_calibration_success_ = false;
}


Expand Down Expand Up @@ -226,7 +230,7 @@ void JointCalibrationController::update()
}
}
else
countdown_ = 200;
countdown_ = tics_moving_past_calibration_reading_;
break;
case MOVING_TO_HIGH: {
vc_.setCommand(search_velocity_);
Expand Down Expand Up @@ -258,13 +262,17 @@ void JointCalibrationController::update()
break;
}
case CALIBRATED:
if (pub_calibrated_) {
if (last_publish_time_ + ros::Duration(0.5) < robot_->getTime()){
assert(pub_calibrated_);
if (pub_calibrated_->trylock()) {
last_publish_time_ = robot_->getTime();
pub_calibrated_->unlockAndPublish();
}
if (!announced_calibration_success_ && pub_zero_offset_ && pub_calibrated_) {
if (pub_zero_offset_->trylock()) {
if (pub_calibrated_->trylock()) {
pub_calibrated_->unlockAndPublish();
pub_zero_offset_->msg_.data = actuator_->state_.zero_offset_;
pub_zero_offset_->unlockAndPublish();
announced_calibration_success_ = true;
}
else {
pub_zero_offset_->unlock();
}
}
}
break;
Expand Down