37 #include "urdf_model/joint.h" 42 #define MAX_DATA_POINTS 120000 47 HysteresisController2::HysteresisController2() :
70 test_data_.arg_name[0] =
"Min. Expected Effort";
71 test_data_.arg_name[1] =
"Max. Expected Effort";
76 test_data_.arg_name[6] =
"Max. Allowed Effort";
108 if (!n.
getParam(
"velocity_controller/joint", name)){
109 ROS_ERROR(
"Hysteresis Controller: No joint name found on parameter namespace: %s)",
115 ROS_ERROR(
"HysteresisController2 could not find joint named \"%s\"\n", name.c_str());
120 ROS_ERROR(
"Hysteresis Controller: No velocity found on parameter namespace: %s)",
127 ROS_ERROR(
"Hysteresis Controller: No max effort found on parameter namespace: %s)",
132 double min_expected, max_expected, max_pos, min_pos;
134 if (!n.
getParam(
"min_expected", min_expected)){
135 ROS_ERROR(
"Hysteresis Controller: No min expected effort found on parameter namespace: %s)",
140 if (!n.
getParam(
"max_expected", max_expected)){
141 ROS_ERROR(
"Hysteresis Controller: No max expected effort found on parameter namespace: %s)",
146 if (!n.
getParam(
"max_position", max_pos)){
147 ROS_ERROR(
"Hysteresis Controller: No max position found on parameter namespace: %s)",
152 if (!n.
getParam(
"min_position", min_pos)){
153 ROS_ERROR(
"Hysteresis Controller: No min position found on parameter namespace: %s)",
159 ROS_ERROR(
"Hysteresis Controller: No timeout found on parameter namespace: %s)",
168 double tolerance, sd_max;
169 if (!n.
getParam(
"tolerance", tolerance)){
170 ROS_WARN(
"Parameter 'tolerance' is not set on namespace: %s. Default is 0.20.",
176 if (!n.
getParam(
"sd_max", sd_max)) {
177 ROS_WARN(
"Parameter 'sd_max' is not set on namespace: %s. Default is 0.20.",
208 double p, i,
d, iClamp, imin;
363 if( count < 1 ) count = 1;
377 joint_qualification_controllers::HysteresisData2 *out = &
hyst_pub_->msg_;
pr2_mechanism_model::JointState * joint_
pr2_mechanism_model::RobotState * robot_
boost::scoped_ptr< realtime_tools::RealtimePublisher< joint_qualification_controllers::HysteresisData2 > > hyst_pub_
void update()
Issues commands to the joint to perform hysteresis test.
bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
Functional way to initialize.
boost::shared_ptr< const urdf::Joint > joint_
void getGains(double &p, double &i, double &d, double &i_max, double &i_min)
controller::JointVelocityController * velocity_controller_
std::vector< int > move_count_
PLUGINLIB_EXPORT_CLASS(joint_qualification_controllers::HysteresisController2, pr2_controller_interface::Controller) using namespace std
void analysis()
Perform the test analysis.
void setCommand(double cmd)
bool sendData()
Sends data, returns true if sent.
const std::string & getNamespace() const
joint_qualification_controllers::HysteresisData2 test_data_
JointState * getJointState(const std::string &name)
bool getParam(const std::string &key, std::string &s) const
void starting()
Called when controller is started.
bool init(pr2_mechanism_model::RobotState *robot, const std::string &joint_name, const control_toolbox::Pid &pid)