40 #ifndef _NOID_ROBOT_HW_H_ 41 #define _NOID_ROBOT_HW_H_ 68 using namespace controller;
86 void writeWheel(
const std::vector< std::string> &_names,
const std::vector<int16_t> &_vel,
double _tm_sec);
87 double getPeriod() {
return ((
double)CONTROL_PERIOD_US_) / (1000 * 1000); }
90 void runHandScript(uint8_t _number, uint16_t _script, uint8_t _current);
91 void writeWheel(std::vector<int16_t> &_vel);
94 void onWheelServo(
bool _value);
99 enum ControlMethod {EFFORT, POSITION, POSITION_PID, VELOCITY, VELOCITY_PID};
unsigned int number_of_angles_
boost::shared_ptr< NoidLowerController > controller_lower_
boost::shared_ptr< NoidUpperController > controller_upper_
std::vector< std::string > joint_names_upper_
std::vector< std::string > joint_list_
int BASE_COMMAND_PERIOD_MS_
std::vector< int16_t > lower_act_strokes_
std::vector< double > joint_effort_
hardware_interface::PositionJointInterface pj_interface_
std::vector< double > prev_ref_positions_
std::vector< JointType > joint_types_
joint_limits_interface::PositionJointSaturationInterface pj_sat_interface_
std::vector< double > joint_position_command_
std::vector< double > joint_effort_limits_
std::vector< double > joint_velocity_
boost::shared_ptr< NoidRobotHW > NoidRobotHWPtr
std::vector< ControlMethod > joint_control_methods_
std::vector< double > joint_effort_command_
void update(controller_manager::ControllerManager &cm, const ros::TimerEvent &e)
std::vector< double > joint_position_
hardware_interface::JointStateInterface js_interface_
std::vector< double > joint_velocity_command_
std::vector< std::string > joint_names_lower_
std::vector< int16_t > upper_act_strokes_