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:
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 );
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 */
DXLPORT_CONTROL::get_error
std::string::size_type get_error(std::string &errorlog)
Definition: dxlport_control.cpp:1064
DXLPORT_CONTROL::set_param_drive_mode
void set_param_drive_mode(uint8_t dxl_id, int val)
Definition: dxlport_control.cpp:760
DXLPORT_CONTROL::~DXLPORT_CONTROL
~DXLPORT_CONTROL()
Definition: dxlport_control.cpp:127
DXLPORT_CONTROL::get_joint_num
uint8_t get_joint_num(void)
Definition: dxlport_control.h:53
DXLPORT_CONTROL::joints
std::vector< JOINT_CONTROL > joints
Definition: dxlport_control.h:74
DXLPORT_CONTROL::set_param_pos_gain_all
void set_param_pos_gain_all(int p, int i, int d)
Definition: dxlport_control.cpp:1003
DXLPORT_CONTROL::set_param_ope_mode
void set_param_ope_mode(uint8_t dxl_id, int val)
Definition: dxlport_control.cpp:787
HOME_MOTION_DATA::start
uint16_t start
Definition: dxlport_control.h:22
hardware_interface::JointStateInterface
DXLPORT_CONTROL::DXLPORT_CONTROL
DXLPORT_CONTROL(ros::NodeHandle handle, CONTROL_SETTING &setting)
Definition: dxlport_control.cpp:16
ros.h
dynamixel::GroupBulkRead
HOME_MOTION_DATA::step
uint16_t step
Definition: dxlport_control.h:24
DXLPORT_CONTROL::set_param_home_offset
void set_param_home_offset(uint8_t dxl_id, int val)
Definition: dxlport_control.cpp:814
DXLPORT_CONTROL::readTemp
void readTemp(ros::Time, ros::Duration)
Definition: dxlport_control.cpp:198
dynamixel::GroupBulkWrite
DXLPORT_CONTROL::set_torque
bool set_torque(uint8_t dxl_id, bool torque)
Definition: dxlport_control.cpp:357
joint_control.h
ST_HOME_MOTION_DATA
struct HOME_MOTION_DATA ST_HOME_MOTION_DATA
DXLPORT_CONTROL::port_stat
bool port_stat
Definition: dxlport_control.h:78
HOME_MOTION_DATA::home_rad
double home_rad
Definition: dxlport_control.h:21
DXLPORT_CONTROL::is_change_positions
bool is_change_positions(void)
Definition: dxlport_control.cpp:291
DXLPORT_CONTROL
Definition: dxlport_control.h:30
DXLPORT_CONTROL::init_stat
bool init_stat
Definition: dxlport_control.h:89
DXLPORT_CONTROL::startup_motion
void startup_motion(void)
Definition: dxlport_control.cpp:413
DXLPORT_CONTROL::joint_num
uint8_t joint_num
Definition: dxlport_control.h:77
DXLPORT_CONTROL::error_queue
std::queue< std::string > error_queue
Definition: dxlport_control.h:94
DXLPORT_CONTROL::set_param_vol_limit
void set_param_vol_limit(uint8_t dxl_id, int max, int min)
Definition: dxlport_control.cpp:895
dynamixel::PortHandler
DXLPORT_CONTROL::get_init_stat
bool get_init_stat(void)
Definition: dxlport_control.h:52
joint_command_interface.h
hardware_interface::RobotHW
DXLPORT_CONTROL::set_torque_all
void set_torque_all(bool torque)
Definition: dxlport_control.cpp:379
DXLPORT_CONTROL::joint_stat_if
hardware_interface::JointStateInterface joint_stat_if
Definition: dxlport_control.h:81
HOME_MOTION_DATA
Definition: dxlport_control.h:19
DXLPORT_CONTROL::getDuration
ros::Duration getDuration(ros::Time t) const
Definition: dxlport_control.h:36
DXLPORT_CONTROL::readCurrent
void readCurrent(ros::Time, ros::Duration)
Definition: dxlport_control.cpp:180
control_setting.h
DXLPORT_CONTROL::write
void write(ros::Time, ros::Duration)
Definition: dxlport_control.cpp:236
DXLPORT_CONTROL::readTempGroup
dynamixel::GroupBulkRead * readTempGroup
Definition: dxlport_control.h:85
hardware_interface::EffortJointInterface
DXLPORT_CONTROL::set_param_moving_threshold
void set_param_moving_threshold(uint8_t dxl_id, int val)
Definition: dxlport_control.cpp:841
DXLPORT_CONTROL::init_joint_params
void init_joint_params(ST_JOINT_PARAM &param, int table_id, int value)
Definition: dxlport_control.cpp:542
DXLPORT_CONTROL::read
bool read(ros::Time, ros::Duration)
Definition: dxlport_control.cpp:137
DXLPORT_CONTROL::set_goal_current_all
void set_goal_current_all(uint16_t current)
Definition: dxlport_control.cpp:330
DXLPORT_CONTROL::readVel
void readVel(ros::Time, ros::Duration)
Definition: dxlport_control.cpp:221
DXLPORT_CONTROL::tempTime
ros::Time tempTime
Definition: dxlport_control.h:92
DXLPORT_CONTROL::rx_err
uint32_t rx_err
Definition: dxlport_control.h:90
DXLPORT_CONTROL::readPos
void readPos(ros::Time, ros::Duration)
Definition: dxlport_control.cpp:162
DXLPORT_CONTROL::set_param_vel_gain
void set_param_vel_gain(uint8_t dxl_id, int p, int i)
Definition: dxlport_control.cpp:962
DXLPORT_CONTROL::writeGoalGroup
dynamixel::GroupBulkWrite * writeGoalGroup
Definition: dxlport_control.h:87
DXLPORT_CONTROL::getTime
ros::Time getTime() const
Definition: dxlport_control.h:35
DXLPORT_CONTROL::set_gain
void set_gain(uint8_t dxl_id, uint16_t gain)
Definition: dxlport_control.cpp:316
joint_state_interface.h
DXLPORT_CONTROL::readMovementGroup
dynamixel::GroupBulkRead * readMovementGroup
Definition: dxlport_control.h:86
CONTROL_SETTING
Definition: control_setting.h:51
ros::Time
DXLPORT_CONTROL::set_gain_all
void set_gain_all(uint16_t gain)
Definition: dxlport_control.cpp:303
DXLPORT_CONTROL::set_param_delay_time
void set_param_delay_time(uint8_t dxl_id, int val)
Definition: dxlport_control.cpp:733
DXLPORT_CONTROL::packetHandler
dynamixel::PacketHandler * packetHandler
Definition: dxlport_control.h:79
DXLPORT_CONTROL::joint_pos_if
hardware_interface::PositionJointInterface joint_pos_if
Definition: dxlport_control.h:82
joint_limits_interface::PositionJointSoftLimitsInterface
DXLPORT_CONTROL::effort_limitter
void effort_limitter(void)
Definition: dxlport_control.cpp:675
DXLPORT_CONTROL::check_servo_param
bool check_servo_param(uint8_t dxl_id, uint32_t test_addr, uint8_t equal, uint8_t &read_val)
Definition: dxlport_control.cpp:481
DXLPORT_CONTROL::set_param_current_limit
void set_param_current_limit(uint8_t dxl_id, int val)
Definition: dxlport_control.cpp:935
DXLPORT_CONTROL::set_param_temp_limit
void set_param_temp_limit(uint8_t dxl_id, int val)
Definition: dxlport_control.cpp:868
DXLPORT_CONTROL::tx_err
uint32_t tx_err
Definition: dxlport_control.h:91
DXLPORT_CONTROL::set_param_pos_gain
void set_param_pos_gain(uint8_t dxl_id, int p, int i, int d)
Definition: dxlport_control.cpp:1010
DXLPORT_CONTROL::portHandler
dynamixel::PortHandler * portHandler
Definition: dxlport_control.h:80
robot_hw.h
dynamixel_sdk.h
DXLPORT_CONTROL::joint_limits_if
joint_limits_interface::PositionJointSoftLimitsInterface joint_limits_if
Definition: dxlport_control.h:84
DXLPORT_CONTROL::joint_eff_if
hardware_interface::EffortJointInterface joint_eff_if
Definition: dxlport_control.h:83
DXLPORT_CONTROL::set_watchdog
void set_watchdog(uint8_t dxl_id, uint8_t value)
Definition: dxlport_control.cpp:388
DXLPORT_CONTROL::self_check
std::string self_check(void)
Definition: dxlport_control.cpp:603
DXLPORT_CONTROL::set_watchdog_all
void set_watchdog_all(uint8_t value)
Definition: dxlport_control.cpp:405
HOME_MOTION_DATA::start_rad
double start_rad
Definition: dxlport_control.h:23
hardware_interface::PositionJointInterface
DXLPORT_CONTROL::tempCount
uint32_t tempCount
Definition: dxlport_control.h:73
ros::Duration
dynamixel::PacketHandler
ST_JOINT_PARAM
Definition: joint_control.h:88
DXLPORT_CONTROL::set_goal_current
void set_goal_current(uint8_t dxl_id, uint16_t current)
Definition: dxlport_control.cpp:343
ros::NodeHandle
HOME_MOTION_DATA::home
uint16_t home
Definition: dxlport_control.h:20
HOME_MOTION_DATA::step_rad
double step_rad
Definition: dxlport_control.h:25
ros::Time::now
static Time now()


crane_x7_control
Author(s): Hiroyuki Nomura , Geoffrey Biggs
autogenerated on Mon Oct 2 2023 02:39:30