49 robot_data_.test_time = -1;
50 robot_data_.num_joints = 0;
51 robot_data_.num_actuators = 0;
83 case (urdf::Joint::FIXED):
86 case (urdf::Joint::REVOLUTE):
89 case (urdf::Joint::CONTINUOUS):
92 case (urdf::Joint::PRISMATIC):
95 case (urdf::Joint::PLANAR):
109 pr2_hardware_interface::ActuatorMap::const_iterator it;
235 joint_qualification_controllers::RobotData *out = &
robot_data_pub_->msg_;
241 out->actuator_data.resize(
robot_data_.num_actuators);
245 out->joint_data[i].index =
robot_data_.joint_data[i].index;
246 out->joint_data[i].name =
robot_data_.joint_data[i].name;
247 out->joint_data[i].is_cal =
robot_data_.joint_data[i].is_cal;
248 out->joint_data[i].has_safety =
robot_data_.joint_data[i].has_safety;
249 out->joint_data[i].type =
robot_data_.joint_data[i].type;
254 out->actuator_data[i].index =
robot_data_.actuator_data[i].index;
255 out->actuator_data[i].name =
robot_data_.actuator_data[i].name;
256 out->actuator_data[i].id =
robot_data_.actuator_data[i].id;
PLUGINLIB_EXPORT_CLASS(joint_qualification_controllers::CheckoutController, pr2_controller_interface::Controller) using namespace std
bool sendData()
Sends data, returns true if sent.
Checkout Controller checks state of PR2 mechanism.
pr2_mechanism_model::RobotState * robot_
pr2_hardware_interface::HardwareInterface * hw_
boost::shared_ptr< const urdf::Joint > joint_
void analysis(double time, bool timeout=false)
Perform the test analysis.
void update()
Checks joint, actuator status for calibrated and enabled.
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void starting()
Called when controller is started or restarted.
std::vector< JointState > joint_states_
joint_qualification_controllers::RobotData robot_data_
boost::scoped_ptr< realtime_tools::RealtimePublisher< joint_qualification_controllers::RobotData > > robot_data_pub_