Go to the documentation of this file.
52 ROS_ERROR(
"Velocity threshold was not specified (namespace: %s)", controller_nh.
getNamespace().c_str());
58 ROS_ERROR(
"Negative velocity threshold is not supported for joint %s. Making the velocity threshold positive.",
61 if (controller_nh.
hasParam(
"return"))
67 ROS_ERROR(
"Position value was not specified (namespace: %s)", nh_return.getNamespace().c_str());
72 ROS_ERROR(
"Position value was not specified (namespace: %s)", nh_return.getNamespace().c_str());
bool init(hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh) override
Get necessary params from param server. Init joint_calibration_controller.
effort_controllers::JointPositionController position_ctrl_
void update(const ros::Time &time, const ros::Duration &period)
bool getParam(const std::string &key, bool &b) const
bool init(hardware_interface::EffortJointInterface *robot, ros::NodeHandle &n)
void update(const ros::Time &time, const ros::Duration &period) override
Execute corresponding action according to current calibration controller state.
std::string getJointName()
void setCommand(double command)
void setOffset(double offset)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
double positive_position_
rm_control::ActuatorExtraHandle actuator_
void update(const ros::Time &time, const ros::Duration &period)
bool init(hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh) override
Get necessary params from param server. Init joint_calibration_controller.
double negative_position_
bool calibration_success_
bool hasParam(const std::string &key) const
hardware_interface::JointHandle joint_
void setCommand(double cmd)
void setCommand(double pos_target)
double getVelocity() const
double getPosition() const
double velocity_threshold_
const std::string & getNamespace() const
void setCalibrated(bool calibrated)
double position_threshold_
double getPosition() const
effort_controllers::JointVelocityController velocity_ctrl_
hardware_interface::JointHandle joint_