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
00040 PLUGINLIB_DECLARE_CLASS(joint_qualification_controllers, MotorJointCalibrationController,
00041 joint_qualification_controllers::MotorJointCalibrationController, pr2_controller_interface::Controller)
00042
00043 using namespace std;
00044 using namespace joint_qualification_controllers;
00045
00046
00047 MotorJointCalibrationController::MotorJointCalibrationController()
00048 : robot_(NULL), last_publish_time_(0), joint_(NULL)
00049 {
00050 }
00051
00052 MotorJointCalibrationController::~MotorJointCalibrationController()
00053 {
00054 }
00055
00056 bool MotorJointCalibrationController::init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
00057 {
00058 robot_ = robot;
00059 node_ = n;
00060
00061
00062
00063 std::string joint_name;
00064 if (!node_.getParam("joint", joint_name))
00065 {
00066 ROS_ERROR("No joint given (namespace: %s)", node_.getNamespace().c_str());
00067 return false;
00068 }
00069 if (!(joint_ = robot->getJointState(joint_name)))
00070 {
00071 ROS_ERROR("Could not find joint %s (namespace: %s)",
00072 joint_name.c_str(), node_.getNamespace().c_str());
00073 return false;
00074 }
00075
00076
00077 pub_calibrated_.reset(
00078 new realtime_tools::RealtimePublisher<std_msgs::Empty>(node_, "calibrated", 1));
00079
00080
00081 joint_->calibrated_ = true;
00082
00083 return true;
00084 }
00085
00086
00087 void MotorJointCalibrationController::update()
00088 {
00089 assert(joint_);
00090
00091 if (pub_calibrated_)
00092 {
00093 if (last_publish_time_ + ros::Duration(0.5) < robot_->getTime())
00094 {
00095 assert(pub_calibrated_);
00096 if (pub_calibrated_->trylock())
00097 {
00098 last_publish_time_ = robot_->getTime();
00099 pub_calibrated_->unlockAndPublish();
00100 }
00101 }
00102 }
00103
00104 }
00105