36 #include "urdf_model/joint.h" 41 #define MAX_DATA_POINTS 120000 46 WristDifferenceController::WristDifferenceController()
112 std::string roll_name;
113 if (!n.
getParam(
"roll_velocity_controller/joint", roll_name)){
114 ROS_ERROR(
"Hysteresis Controller: No joint name found on parameter namespace: %s)",
120 ROS_ERROR(
"WristDifferenceController could not find joint named \"%s\"\n", roll_name.c_str());
123 ROS_DEBUG(
"Roll joint: %s", roll_name.c_str());
126 ROS_ERROR(
"Wrist roll joint must be continuous. Unable to check wrist symmetry. Roll joint: %s", roll_name.c_str());
131 ROS_ERROR(
"Hysteresis Controller: No velocity found on parameter namespace: %s)",
137 std::string flex_name;
138 if (!n.
getParam(
"flex_position_controller/joint", flex_name)){
139 ROS_ERROR(
"Hysteresis Controller: No joint name found on parameter namespace: %s)",
145 ROS_ERROR(
"WristDifferenceController could not find joint named \"%s\"\n", flex_name.c_str());
150 ROS_ERROR(
"Hysteresis Controller: No velocity found on parameter namespace: %s)",
156 ROS_ERROR(
"Hysteresis Controller: No timeout found on parameter namespace: %s)",
162 ROS_WARN(
"Parameter 'tolerance' is not set on namespace: %s.",
168 ROS_WARN(
"Parameter 'sd_max' is not set on namespace: %s.",
173 double left_effort, right_effort, flex_tolerance, flex_max, flex_sd;
174 if (!n.
getParam(
"left_effort", left_effort)) {
175 ROS_WARN(
"Parameter 'left_effort' is not set on namespace: %s.",
180 if (!n.
getParam(
"right_effort", right_effort)) {
181 ROS_WARN(
"Parameter 'right_effort' is not set on namespace: %s.",
186 if (!n.
getParam(
"flex_tolerance", flex_tolerance)) {
187 ROS_WARN(
"Parameter 'flex_tolerance' is not set on namespace: %s.",
193 if (!n.
getParam(
"flex_max", flex_max)) {
194 ROS_WARN(
"Parameter 'flex_max' is not set on namespace: %s.",
199 if (!n.
getParam(
"flex_sd", flex_sd)) {
200 ROS_WARN(
"Parameter 'flex_sd' is not set on namespace: %s.",
230 double p, i,
d, iClamp, imin;
380 joint_qualification_controllers::WristDiffData *out = &
wrist_data_pub_->msg_;
void analysis()
Perform the test analysis.
void setCommand(double cmd)
~WristDifferenceController()
boost::shared_ptr< const urdf::Joint > joint_
controller::JointPositionController * flex_controller_
void getGains(double &p, double &i, double &d, double &i_max, double &i_min)
pr2_mechanism_model::JointState * flex_joint_
boost::scoped_ptr< realtime_tools::RealtimePublisher< joint_qualification_controllers::WristDiffData > > wrist_data_pub_
joint_qualification_controllers::WristDiffData wrist_test_data_
void setCommand(double cmd)
pr2_mechanism_model::JointState * roll_joint_
bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
Functional way to initialize.
void starting()
Called when controller is started.
const std::string & getNamespace() const
pr2_mechanism_model::RobotState * robot_
JointState * getJointState(const std::string &name)
controller::JointVelocityController * roll_controller_
bool sendData()
Sends data, returns true if sent.
bool init(pr2_mechanism_model::RobotState *robot, const std::string &joint_name, const control_toolbox::Pid &pid)
void update()
Issues commands to the joint to perform hysteresis test.
void getGains(double &p, double &i, double &d, double &i_max, double &i_min)
bool getParam(const std::string &key, std::string &s) const
PLUGINLIB_EXPORT_CLASS(joint_qualification_controllers::WristDifferenceController, pr2_controller_interface::Controller) using namespace std
bool init(pr2_mechanism_model::RobotState *robot, const std::string &joint_name, const control_toolbox::Pid &pid)