37 #include "urdf_model/joint.h" 42 #define MAX_DATA_POINTS 120000 47 HysteresisController::HysteresisController() :
66 test_data_.arg_name[0] =
"Min. Expected Effort";
67 test_data_.arg_name[1] =
"Max. Expected Effort";
72 test_data_.arg_name[6] =
"Max. Allowed Effort";
102 if (!n.
getParam(
"velocity_controller/joint", name)){
103 ROS_ERROR(
"Hysteresis Controller: No joint name found on parameter namespace: %s)",
109 ROS_ERROR(
"HysteresisController could not find joint named \"%s\"\n", name.c_str());
114 ROS_ERROR(
"Hysteresis Controller: No velocity found on parameter namespace: %s)",
121 ROS_ERROR(
"Hysteresis Controller: No max effort found on parameter namespace: %s)",
126 double min_expected, max_expected, max_pos, min_pos;
128 if (!n.
getParam(
"min_expected", min_expected)){
129 ROS_ERROR(
"Hysteresis Controller: No min expected effort found on parameter namespace: %s)",
134 if (!n.
getParam(
"max_expected", max_expected)){
135 ROS_ERROR(
"Hysteresis Controller: No max expected effort found on parameter namespace: %s)",
140 if (!n.
getParam(
"max_position", max_pos)){
141 ROS_ERROR(
"Hysteresis Controller: No max position found on parameter namespace: %s)",
146 if (!n.
getParam(
"min_position", min_pos)){
147 ROS_ERROR(
"Hysteresis Controller: No min position found on parameter namespace: %s)",
153 ROS_ERROR(
"Hysteresis Controller: No timeout found on parameter namespace: %s)",
158 double tolerance, sd_max;
159 if (!n.
getParam(
"tolerance", tolerance)){
160 ROS_WARN(
"Parameter 'tolerance' is not set on namespace: %s. Default is 0.20.",
166 if (!n.
getParam(
"sd_max", sd_max)) {
167 ROS_WARN(
"Parameter 'sd_max' is not set on namespace: %s. Default is 0.20.",
198 double p, i,
d, iClamp, imin;
342 joint_qualification_controllers::HysteresisData *out = &
hyst_pub_->msg_;
352 out->position_down =
test_data_.position_down;
353 out->velocity_down =
test_data_.velocity_down;
void update()
Issues commands to the joint to perform hysteresis test.
PLUGINLIB_EXPORT_CLASS(joint_qualification_controllers::HysteresisController, pr2_controller_interface::Controller) using namespace std
pr2_mechanism_model::RobotState * robot_
void analysis()
Perform the test analysis.
boost::shared_ptr< const urdf::Joint > joint_
void getGains(double &p, double &i, double &d, double &i_max, double &i_min)
bool sendData()
Sends data, returns true if sent.
bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
Functional way to initialize.
void setCommand(double cmd)
controller::JointVelocityController * velocity_controller_
const std::string & getNamespace() const
JointState * getJointState(const std::string &name)
joint_qualification_controllers::HysteresisData test_data_
boost::scoped_ptr< realtime_tools::RealtimePublisher< joint_qualification_controllers::HysteresisData > > hyst_pub_
bool getParam(const std::string &key, std::string &s) const
void starting()
Called when controller is started.
pr2_mechanism_model::JointState * joint_
bool init(pr2_mechanism_model::RobotState *robot, const std::string &joint_name, const control_toolbox::Pid &pid)