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 "pr2_calibration_controllers/fake_calibration_controller.h"
00036 #include "ros/time.h"
00037 #include "pluginlib/class_list_macros.h"
00038
00039 using namespace std;
00040 using namespace controller;
00041
00042 PLUGINLIB_DECLARE_CLASS(pr2_calibration_controllers, FakeCalibrationController,
00043 controller::FakeCalibrationController, pr2_controller_interface::Controller)
00044
00045 namespace controller
00046 {
00047
00048 FakeCalibrationController::FakeCalibrationController()
00049 : last_publish_time_(0), joint_(NULL)
00050 {
00051 }
00052
00053 FakeCalibrationController::~FakeCalibrationController()
00054 {
00055 }
00056
00057 bool FakeCalibrationController::init(pr2_mechanism_model::RobotState *robot,
00058 ros::NodeHandle &n)
00059 {
00060 assert(robot);
00061 robot_ = robot;
00062 node_ = n;
00063
00064 std::string joint_name;
00065 if (!node_.getParam("joint", joint_name))
00066 {
00067 ROS_ERROR("No joint given (namespace: %s)", node_.getNamespace().c_str());
00068 return false;
00069 }
00070 if (!(joint_ = robot->getJointState(joint_name)))
00071 {
00072 ROS_ERROR("Could not find joint \"%s\" (namespace: %s)",
00073 joint_name.c_str(), node_.getNamespace().c_str());
00074 return false;
00075 }
00076
00077
00078 is_calibrated_srv_ = node_.advertiseService("is_calibrated", &FakeCalibrationController::isCalibrated, this);
00079
00080
00081 pub_calibrated_.reset(new realtime_tools::RealtimePublisher<std_msgs::Empty>(node_, "calibrated", 1));
00082
00083 return true;
00084 }
00085
00086
00087 void FakeCalibrationController::starting()
00088 {
00089 }
00090
00091
00092 bool FakeCalibrationController::isCalibrated(pr2_controllers_msgs::QueryCalibrationState::Request& req,
00093 pr2_controllers_msgs::QueryCalibrationState::Response& resp)
00094 {
00095 resp.is_calibrated = joint_->calibrated_;
00096 return true;
00097 }
00098
00099
00100 void FakeCalibrationController::update()
00101 {
00102 assert(joint_);
00103 joint_->calibrated_ = true;
00104 }
00105
00106 }