50 lift_controller_(NULL),
51 flex_controller_(NULL),
62 cb_test_data_.arg_name.resize(25);
63 cb_test_data_.arg_value.resize(25);
64 cb_test_data_.arg_name[0] =
"Settle Time";
65 cb_test_data_.arg_name[1] =
"Dither Points";
66 cb_test_data_.arg_name[2] =
"Timeout";
67 cb_test_data_.arg_name[3] =
"Lift Min";
68 cb_test_data_.arg_name[4] =
"Lift Max";
69 cb_test_data_.arg_name[5] =
"Lift Delta";
70 cb_test_data_.arg_name[6] =
"Flex Min";
71 cb_test_data_.arg_name[7] =
"Flex Max";
72 cb_test_data_.arg_name[8] =
"Flex Delta";
75 cb_test_data_.arg_name[9] =
"Lift MSE";
76 cb_test_data_.arg_name[10] =
"Lift Avg Abs";
77 cb_test_data_.arg_name[11] =
"Lift Avg Effort";
78 cb_test_data_.arg_name[12] =
"Flex MSE";
79 cb_test_data_.arg_name[13] =
"Flex Avg Abs";
80 cb_test_data_.arg_name[14] =
"Flex Avg Effort";
83 cb_test_data_.arg_name[15] =
"Lift P";
84 cb_test_data_.arg_name[16] =
"Lift I";
85 cb_test_data_.arg_name[17] =
"Lift D";
86 cb_test_data_.arg_name[18] =
"Lift I Clamp";
88 cb_test_data_.arg_name[19] =
"Flex P";
89 cb_test_data_.arg_name[20] =
"Flex I";
90 cb_test_data_.arg_name[21] =
"Flex D";
91 cb_test_data_.arg_name[22] =
"Flex I Clamp";
93 cb_test_data_.arg_name[23] =
"Screw Tolerance";
94 cb_test_data_.arg_name[24] =
"Bar Tolerance";
96 cb_test_data_.timeout_hit =
false;
97 cb_test_data_.lift_joint =
"None";
98 cb_test_data_.lift_joint =
"";
99 cb_test_data_.lift_amplitude = 0;
100 cb_test_data_.flex_amplitude = 0;
108 CounterbalanceTestController::~CounterbalanceTestController()
123 if (!n.
getParam(
"lift/joint", lift_joint)){
124 ROS_ERROR(
"CounterbalanceTestController: No lift joint name found on parameter namespace: %s)",
130 ROS_ERROR(
"CounterbalanceTestController could not find lift joint named \"%s\"\n", lift_joint.c_str());
142 double flex_delta = 0;
144 double flex_avg_abs = 0;
145 double flex_avg_eff = 0;
151 if (n.
getParam(
"flex/joint", flex_joint))
157 ROS_ERROR(
"CounterbalanceTestController could not find flex joint named \"%s\"\n", flex_joint.c_str());
163 if (!n.
getParam(
"flex/min", flex_min))
165 ROS_ERROR(
"CounterbalanceTestController: No min flex position found on parameter namespace: %s)",
169 if (!n.
getParam(
"flex/max", flex_max))
171 ROS_ERROR(
"CounterbalanceTestController: No max flex position found on parameter namespace: %s)",
175 if (!n.
getParam(
"flex/delta", flex_delta))
177 ROS_ERROR(
"CounterbalanceTestController: No flex delta found on parameter namespace: %s)",
182 if (flex_max < flex_min)
184 ROS_ERROR(
"CounterbalanceTestController: Flex max position must be >= flex min position");
189 ROS_ERROR(
"CounterbalanceTestController: \"flex_delta\" parameter must be >=0");
193 num_flexs = (int)(((flex_max - flex_min) / flex_delta) + 1);
196 if (!n.
getParam(
"flex/mse", flex_mse))
198 ROS_ERROR(
"CounterbalanceTestController: No flex/mse (mean square effort) found on parameter namespace: %s)",
203 if (!n.
getParam(
"flex/avg_abs", flex_avg_abs))
205 ROS_ERROR(
"CounterbalanceTestController: No flex/avg_abs (average absolute effort) found on parameter namespace: %s)",
210 if (!n.
getParam(
"flex/avg_eff", flex_avg_eff))
212 ROS_ERROR(
"CounterbalanceTestController: No flex/avg_eff (average absolute effort) found on parameter namespace: %s)",
217 double flex_amplitude;
218 if (!n.
getParam(
"flex/dither", flex_amplitude))
220 ROS_ERROR(
"CounterbalanceTestController: No flex amplitude found on parameter namespace: %s)",
233 ROS_INFO(
"Initializing CounterbalanceTestController as a lift and flex test. Namespace: %s",
238 ROS_INFO(
"Initializing CounterbalanceTestController as a shoulder lift test only. Namespace: %s",
242 double lift_amplitude;
243 if (!n.
getParam(
"lift/dither", lift_amplitude))
245 ROS_ERROR(
"CounterbalanceTestController: No lift amplitude found on parameter namespace: %s)",
255 double lift_min, lift_max, lift_delta;
256 if (!n.
getParam(
"lift/min", lift_min))
258 ROS_ERROR(
"CounterbalanceTestController: No min lift position found on parameter namespace: %s)",
262 if (!n.
getParam(
"lift/max", lift_max))
264 ROS_ERROR(
"CounterbalanceTestController: No max lift position found on parameter namespace: %s)",
268 if (lift_max < lift_min)
270 ROS_ERROR(
"CounterbalanceTestController was given a shoulder lift maximum with values less than its minimum. Max: %f, Min %f", lift_max, lift_min);
274 if (!n.
getParam(
"lift/delta", lift_delta))
276 ROS_ERROR(
"CounterbalanceTestController: No lift delta found on parameter namespace: %s)",
282 ROS_ERROR(
"CounterbalanceTestController was given a shoulder lift position delta <0. Delta given: %f", lift_delta);
289 ROS_ERROR(
"CounterbalanceTestController: No settle time found on parameter namespace: %s)",
296 ROS_ERROR(
"CounterbalanceTestController: No dither points param found on parameter namespace: %s)",
303 ROS_ERROR(
"CounterbalanceTestController: No timeout found on parameter namespace: %s)",
308 double lift_mse, lift_avg_abs, lift_avg_eff;
309 if (!n.
getParam(
"lift/mse", lift_mse))
311 ROS_ERROR(
"CounterbalanceTestController: No lift/mse (mean square effort) found on parameter namespace: %s)",
316 if (!n.
getParam(
"lift/avg_abs", lift_avg_abs))
318 ROS_ERROR(
"CounterbalanceTestController: No lift/avg_abs (average absolute effort) found on parameter namespace: %s)",
323 if (!n.
getParam(
"lift/avg_eff", lift_avg_eff))
325 ROS_ERROR(
"CounterbalanceTestController: No lift/avg_eff (average absolute effort) found on parameter namespace: %s)",
333 num_lifts = (int)((lift_max - lift_min)/lift_delta + 1);
337 for (
int i = 0; i < num_lifts; ++i)
339 cb_test_data_.lift_data[i].lift_position = (double)lift_min + lift_delta * i;
341 for (
int j = 0; j < num_flexs; ++j)
343 cb_test_data_.lift_data[i].flex_data[j].flex_position = (double)flex_min + flex_delta * ((
double)j);
385 double p, i,
d, i_clamp, dummy;
409 double screw_tol, bar_tol;
410 if (!n.
getParam(
"screw_tol", screw_tol))
412 ROS_INFO(
"CounterbalanceTestController was not given parameter 'screw_tol' on namespace %s. Using default 2.0",
417 if (!n.
getParam(
"bar_tol", bar_tol))
419 ROS_INFO(
"CounterbalanceTestController was not given parameter 'bar_tol' on namespace %s. Using default 0.8",
428 joint_qualification_controllers::CounterbalanceTestData>(n,
"/cb_test_data", 1,
true));
452 ROS_WARN(
"CounterbalanceTestController timed out during test. Timeout: %f.",
timeout_);
558 joint_qualification_controllers::CounterbalanceTestData *out = &
cb_data_pub_->msg_;
pr2_mechanism_model::JointState * lift_state_
void setCommand(double cmd)
control_toolbox::Dither * lift_dither_
controller::JointPositionController * lift_controller_
pr2_mechanism_model::JointState * flex_state_
const std::string & getNamespace() const
JointState * getJointState(const std::string &name)
pr2_mechanism_model::RobotState * robot_
bool init(pr2_mechanism_model::RobotState *robot, const std::string &joint_name, const control_toolbox::Pid &pid)
void update()
Issues commands to the joint. Should be called at regular intervals.
void getGains(double &p, double &i, double &d, double &i_max, double &i_min)
joint_qualification_controllers::CounterbalanceTestData cb_test_data_
bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
Functional way to initialize.
control_toolbox::Dither * flex_dither_
PLUGINLIB_EXPORT_CLASS(joint_qualification_controllers::CounterbalanceTestController, pr2_controller_interface::Controller) using namespace std
bool getParam(const std::string &key, std::string &s) const
controller::JointPositionController * flex_controller_
boost::scoped_ptr< realtime_tools::RealtimePublisher< joint_qualification_controllers::CounterbalanceTestData > > cb_data_pub_