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 "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_EXPORT_CLASS(controller::FakeCalibrationController, pr2_controller_interface::Controller)
00043
00044 namespace controller
00045 {
00046
00047 FakeCalibrationController::FakeCalibrationController()
00048 : last_publish_time_(0), joint_(NULL)
00049 {
00050 }
00051
00052 FakeCalibrationController::~FakeCalibrationController()
00053 {
00054 }
00055
00056 bool FakeCalibrationController::init(pr2_mechanism_model::RobotState *robot,
00057 ros::NodeHandle &n)
00058 {
00059 assert(robot);
00060 robot_ = robot;
00061 node_ = n;
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 is_calibrated_srv_ = node_.advertiseService("is_calibrated", &FakeCalibrationController::isCalibrated, this);
00078
00079
00080 pub_calibrated_.reset(new realtime_tools::RealtimePublisher<std_msgs::Empty>(node_, "calibrated", 1));
00081
00082 return true;
00083 }
00084
00085
00086 void FakeCalibrationController::starting()
00087 {
00088 }
00089
00090
00091 bool FakeCalibrationController::isCalibrated(pr2_controllers_msgs::QueryCalibrationState::Request& req,
00092 pr2_controllers_msgs::QueryCalibrationState::Response& resp)
00093 {
00094 resp.is_calibrated = joint_->calibrated_;
00095 return true;
00096 }
00097
00098
00099 void FakeCalibrationController::update()
00100 {
00101 assert(joint_);
00102 joint_->calibrated_ = true;
00103 }
00104
00105 }