Go to the documentation of this file.
47 GripperCalibrationController::GripperCalibrationController()
48 : last_publish_time_(0), joint_(NULL)
75 for (
int i = 0;
i < other_joint_names.
size(); ++
i)
78 std::string name = (std::string)other_joint_names[
i];
83 ROS_ERROR(
"Could not find joint \"%s\" (namespace: %s)",
97 std::string joint_name;
105 ROS_ERROR(
"Could not find joint \"%s\" (namespace: %s)",
110 std::string actuator_name;
118 ROS_ERROR(
"Could not find actuator \"%s\" (namespace: %s)",
123 bool force_calibration =
false;
129 if (force_calibration)
131 ROS_INFO(
"Joint %s will be recalibrated, but was already calibrated at offset %f",
144 ROS_INFO(
"Joint %s is not yet calibrated", joint_name.c_str());
169 pr2_controllers_msgs::QueryCalibrationState::Response& resp)
pr2_mechanism_model::RobotState * robot_
bool getParam(const std::string &key, bool &b) const
pr2_mechanism_model::JointState * joint_
pr2_hardware_interface::Actuator * getActuator(const std::string &name) const
std::vector< pr2_mechanism_model::JointState * > other_joints_
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
bool init(pr2_mechanism_model::RobotState *robot, const std::string &joint_name, const control_toolbox::Pid &pid)
ros::ServiceServer is_calibrated_srv_
bool isCalibrated(pr2_controllers_msgs::QueryCalibrationState::Request &req, pr2_controllers_msgs::QueryCalibrationState::Response &resp)
controller::JointVelocityController vc_
JointState * getJointState(const std::string &name)
double stopped_velocity_tolerance_
PLUGINLIB_EXPORT_CLASS(my_controller_ns::MyControllerClass, pr2_controller_interface::Controller)
const Type & getType() const
boost::scoped_ptr< realtime_tools::RealtimePublisher< std_msgs::Empty > > pub_calibrated_
~GripperCalibrationController()
virtual bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
pr2_hardware_interface::Actuator * actuator_
T param(const std::string ¶m_name, const T &default_val) const
ros::Time last_publish_time_
const std::string & getNamespace() const
void setCommand(double cmd)