motor_joint_calibration_controller.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2009, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
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   // Joint
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   // "Calibrated" topic
00077   pub_calibrated_.reset(
00078     new realtime_tools::RealtimePublisher<std_msgs::Empty>(node_, "calibrated", 1));
00079 
00080   // Calibrate at zero, basically
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 


joint_qualification_controllers
Author(s): Kevin Watts, Melonee Wise
autogenerated on Mon Sep 14 2015 14:38:58