47 FakeCalibrationController::FakeCalibrationController()
48 : last_publish_time_(0), joint_(NULL)
63 std::string joint_name;
71 ROS_ERROR(
"Could not find joint \"%s\" (namespace: %s)",
92 pr2_controllers_msgs::QueryCalibrationState::Response& resp)
PLUGINLIB_EXPORT_CLASS(my_controller_ns::MyControllerClass, pr2_controller_interface::Controller)
pr2_mechanism_model::RobotState * robot_
pr2_mechanism_model::JointState * joint_
ros::ServiceServer is_calibrated_srv_
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
~FakeCalibrationController()
const std::string & getNamespace() const
JointState * getJointState(const std::string &name)
boost::scoped_ptr< realtime_tools::RealtimePublisher< std_msgs::Empty > > pub_calibrated_
bool getParam(const std::string &key, std::string &s) const
virtual bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
bool isCalibrated(pr2_controllers_msgs::QueryCalibrationState::Request &req, pr2_controllers_msgs::QueryCalibrationState::Response &resp)