Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #include "joint_qualification_controllers/motor_joint_calibration_controller.h"
00036 #include "ros/time.h"
00037 #include "pluginlib/class_list_macros.h"
00038
00039 PLUGINLIB_EXPORT_CLASS(joint_qualification_controllers::MotorJointCalibrationController, pr2_controller_interface::Controller)
00040
00041 using namespace std;
00042 using namespace joint_qualification_controllers;
00043
00044
00045 MotorJointCalibrationController::MotorJointCalibrationController()
00046 : robot_(NULL), last_publish_time_(0), joint_(NULL)
00047 {
00048 }
00049
00050 MotorJointCalibrationController::~MotorJointCalibrationController()
00051 {
00052 }
00053
00054 bool MotorJointCalibrationController::init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
00055 {
00056 robot_ = robot;
00057 node_ = n;
00058
00059
00060
00061 std::string joint_name;
00062 if (!node_.getParam("joint", joint_name))
00063 {
00064 ROS_ERROR("No joint given (namespace: %s)", node_.getNamespace().c_str());
00065 return false;
00066 }
00067 if (!(joint_ = robot->getJointState(joint_name)))
00068 {
00069 ROS_ERROR("Could not find joint %s (namespace: %s)",
00070 joint_name.c_str(), node_.getNamespace().c_str());
00071 return false;
00072 }
00073
00074
00075 pub_calibrated_.reset(
00076 new realtime_tools::RealtimePublisher<std_msgs::Empty>(node_, "calibrated", 1));
00077
00078
00079 joint_->calibrated_ = true;
00080
00081 return true;
00082 }
00083
00084
00085 void MotorJointCalibrationController::update()
00086 {
00087 assert(joint_);
00088
00089 if (pub_calibrated_)
00090 {
00091 if (last_publish_time_ + ros::Duration(0.5) < robot_->getTime())
00092 {
00093 assert(pub_calibrated_);
00094 if (pub_calibrated_->trylock())
00095 {
00096 last_publish_time_ = robot_->getTime();
00097 pub_calibrated_->unlockAndPublish();
00098 }
00099 }
00100 }
00101
00102 }
00103