Skip to content

Commit e3e7cf8

Browse files
v4hnpr2
authored andcommitted
publish calibrated zero_offset & latch publishers
There is no reason to publish messages with 2Hz to say calibration completed.
1 parent edf4cab commit e3e7cf8

File tree

2 files changed

+19
-12
lines changed

2 files changed

+19
-12
lines changed

pr2_calibration_controllers/include/pr2_calibration_controllers/joint_calibration_controller.h

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -43,6 +43,7 @@
4343
#include "robot_mechanism_controllers/joint_velocity_controller.h"
4444
#include "realtime_tools/realtime_publisher.h"
4545
#include "std_msgs/Empty.h"
46+
#include "std_msgs/Float32.h"
4647
#include "pr2_controllers_msgs/QueryCalibrationState.h"
4748

4849

@@ -65,12 +66,13 @@ class JointCalibrationController : public pr2_controller_interface::Controller
6566
protected:
6667
pr2_mechanism_model::RobotState* robot_;
6768
ros::NodeHandle node_;
68-
ros::Time last_publish_time_;
6969
ros::ServiceServer is_calibrated_srv_;
7070
boost::scoped_ptr<realtime_tools::RealtimePublisher<std_msgs::Empty> > pub_calibrated_;
71+
boost::scoped_ptr<realtime_tools::RealtimePublisher<std_msgs::Float32> > pub_zero_offset_;
7172

7273
enum { INITIALIZED, BEGINNING, MOVING_TO_LOW, MOVING_TO_HIGH, CALIBRATED };
7374
int state_;
75+
bool announced_calibration_success_;
7476
int countdown_;
7577

7678
double search_velocity_;

pr2_calibration_controllers/src/joint_calibration_controller.cpp

Lines changed: 16 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -43,8 +43,7 @@ using namespace std;
4343
namespace controller {
4444

4545
JointCalibrationController::JointCalibrationController()
46-
: robot_(NULL), last_publish_time_(0),
47-
actuator_(NULL), joint_(NULL)
46+
: robot_(NULL), actuator_(NULL), joint_(NULL)
4847
{
4948
}
5049

@@ -96,6 +95,7 @@ bool JointCalibrationController::init(pr2_mechanism_model::RobotState *robot, ro
9695

9796
state_ = INITIALIZED;
9897
joint_->calibrated_ = false;
98+
announced_calibration_success_ = false;
9999
if (actuator_->state_.zero_offset_ != 0)
100100
{
101101
if (force_calibration)
@@ -173,8 +173,8 @@ bool JointCalibrationController::init(pr2_mechanism_model::RobotState *robot, ro
173173
is_calibrated_srv_ = node_.advertiseService("is_calibrated", &JointCalibrationController::isCalibrated, this);
174174

175175
// "Calibrated" topic
176-
pub_calibrated_.reset(new realtime_tools::RealtimePublisher<std_msgs::Empty>(node_, "calibrated", 1));
177-
176+
pub_calibrated_.reset(new realtime_tools::RealtimePublisher<std_msgs::Empty>(node_, "calibrated", 1, true));
177+
pub_zero_offset_.reset(new realtime_tools::RealtimePublisher<std_msgs::Float32>(node_, "zero_offset", 1, true));
178178

179179
return true;
180180
}
@@ -185,6 +185,7 @@ void JointCalibrationController::starting()
185185
state_ = INITIALIZED;
186186
joint_->calibrated_ = false;
187187
actuator_->state_.zero_offset_ = 0.0;
188+
announced_calibration_success_ = false;
188189
}
189190

190191

@@ -258,13 +259,17 @@ void JointCalibrationController::update()
258259
break;
259260
}
260261
case CALIBRATED:
261-
if (pub_calibrated_) {
262-
if (last_publish_time_ + ros::Duration(0.5) < robot_->getTime()){
263-
assert(pub_calibrated_);
264-
if (pub_calibrated_->trylock()) {
265-
last_publish_time_ = robot_->getTime();
266-
pub_calibrated_->unlockAndPublish();
267-
}
262+
if (!announced_calibration_success_ && pub_zero_offset_ && pub_calibrated_) {
263+
if (pub_zero_offset_->trylock()) {
264+
if (pub_calibrated_->trylock()) {
265+
pub_calibrated_->unlockAndPublish();
266+
pub_zero_offset_->msg_.data = actuator_->state_.zero_offset_;
267+
pub_zero_offset_->unlockAndPublish();
268+
announced_calibration_success_ = true;
269+
}
270+
else {
271+
pub_zero_offset_->unlock();
272+
}
268273
}
269274
}
270275
break;

0 commit comments

Comments
 (0)