dxlport_control.h
Go to the documentation of this file.
1 #ifndef DXLPORT_CONTROL_H
2 #define DXLPORT_CONTROL_H
3 
4 #include <map>
5 #include <string>
6 #include <vector>
7 #include <queue>
8 #include <ros/ros.h>
12 
16 
17 
18 // Motion data
19 typedef struct HOME_MOTION_DATA {
20  uint16_t home;
21  double home_rad;
22  uint16_t start;
23  double start_rad;
24  uint16_t step;
25  double step_rad;
27 
28 
29 // Dynamixel protocol serial port class
31 {
32 public:
34  ~DXLPORT_CONTROL();
35  ros::Time getTime() const { return ros::Time::now(); }
36  ros::Duration getDuration( ros::Time t ) const { return (ros::Time::now() - t); }
37  bool read( ros::Time, ros::Duration );
38  void readPos( ros::Time, ros::Duration );
39  void readCurrent( ros::Time, ros::Duration );
40  void readTemp( ros::Time, ros::Duration );
41  void readVel( ros::Time, ros::Duration );
42  void write( ros::Time, ros::Duration );
43  void set_torque_all( bool torque );
44  bool set_torque( uint8_t dxl_id, bool torque );
45  void set_watchdog( uint8_t dxl_id, uint8_t value );
46  void set_watchdog_all( uint8_t value );
47  void startup_motion( void );
48  void set_gain_all( uint16_t gain );
49  void set_gain( uint8_t dxl_id, uint16_t gain );
50  void set_goal_current_all( uint16_t current );
51  void set_goal_current( uint8_t dxl_id, uint16_t current );
52  bool get_init_stat( void ){ return init_stat; }
53  uint8_t get_joint_num( void ){ return joint_num; }
54  std::string self_check( void );
55  void effort_limitter( void );
56  void init_joint_params( ST_JOINT_PARAM &param, int table_id, int value );
57 
58  void set_param_delay_time( uint8_t dxl_id, int val );
59  void set_param_drive_mode( uint8_t dxl_id, int val );
60  void set_param_ope_mode( uint8_t dxl_id, int val );
61  void set_param_home_offset( uint8_t dxl_id, int val );
62  void set_param_moving_threshold( uint8_t dxl_id, int val );
63  void set_param_temp_limit( uint8_t dxl_id, int val );
64  void set_param_vol_limit( uint8_t dxl_id, int max, int min );
65  void set_param_current_limit( uint8_t dxl_id, int val );
66  void set_param_vel_gain( uint8_t dxl_id, int p, int i );
67  void set_param_pos_gain_all( int p, int i, int d );
68  void set_param_pos_gain( uint8_t dxl_id, int p, int i, int d );
69 
70  bool is_change_positions( void );
71  std::string::size_type get_error( std::string& errorlog );
72 
73  uint32_t tempCount;
74  std::vector<JOINT_CONTROL> joints;
75 
76 private:
77  uint8_t joint_num;
78  bool port_stat;
88 
89  bool init_stat;
90  uint32_t rx_err;
91  uint32_t tx_err;
93 
94  std::queue<std::string> error_queue;
95 
96  bool check_servo_param( uint8_t dxl_id, uint32_t test_addr, uint8_t equal, uint8_t& read_val );
97  bool check_servo_param( uint8_t dxl_id, uint32_t test_addr, uint16_t equal, uint16_t& read_val );
98  bool check_servo_param( uint8_t dxl_id, uint32_t test_addr, uint32_t equal, uint32_t& read_val );
99 };
100 
101 #endif /* DXLPORT_CONTROL_H */
d
bool param(const std::string &param_name, T &param_val, const T &default_val)
std::queue< std::string > error_queue
hardware_interface::JointStateInterface joint_stat_if
bool get_init_stat(void)
ros::Time tempTime
struct HOME_MOTION_DATA ST_HOME_MOTION_DATA
dynamixel::GroupBulkRead * readTempGroup
dynamixel::GroupBulkWrite * writeGoalGroup
int min(int a, int b)
hardware_interface::EffortJointInterface joint_eff_if
dynamixel::GroupBulkRead * readMovementGroup
static Time now()
hardware_interface::PositionJointInterface joint_pos_if
ros::Time getTime() const
dynamixel::PacketHandler * packetHandler
std::vector< JOINT_CONTROL > joints
ros::Duration getDuration(ros::Time t) const
uint8_t get_joint_num(void)
dynamixel::PortHandler * portHandler
joint_limits_interface::PositionJointSoftLimitsInterface joint_limits_if


crane_x7_control
Author(s): Hiroyuki Nomura , Geoffrey Biggs
autogenerated on Mon Mar 1 2021 03:18:36