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 
13 #include <dynamixel_sdk/dynamixel_sdk.h> // Uses Dynamixel SDK library
16 
17 #include "device_mutex.h"
18 
19 // Motion data
20 typedef struct HOME_MOTION_DATA {
21  uint16_t home;
22  double home_rad;
23  uint16_t start;
24  double start_rad;
25  uint16_t step;
26  double step_rad;
28 
29 
30 // Dynamixel protocol serial port class
32 {
33 public:
36  ros::Time getTime() const { return ros::Time::now(); }
37  ros::Duration getDuration( ros::Time t ) const { return (ros::Time::now() - t); }
38  bool read( ros::Time, ros::Duration );
44  void write( ros::Time, ros::Duration );
45  void set_torque_all( bool torque );
46  bool set_torque( uint8_t dxl_id, bool torque );
47  void set_watchdog( uint8_t dxl_id, uint8_t value );
48  void set_watchdog_all( uint8_t value );
49  void startup_motion( void );
50  void set_gain_all( uint16_t gain );
51  void set_gain( uint8_t dxl_id, uint16_t gain );
52  void set_goal_current_all( uint16_t current );
53  void set_goal_current( uint8_t dxl_id, uint16_t current );
54  bool get_init_stat( void ){ return init_stat; }
55  uint8_t get_joint_num( void ){ return joint_num; }
56  std::string self_check( void );
57  void init_joint_params( ST_JOINT_PARAM &param, int table_id, int value );
58 
59  void set_param_delay_time( uint8_t dxl_id, int val );
60  void set_param_drive_mode( uint8_t dxl_id, int val );
61  void set_param_ope_mode( uint8_t dxl_id, int val );
62  void set_param_home_offset( uint8_t dxl_id, int val );
63  void set_param_moving_threshold( uint8_t dxl_id, int val );
64  void set_param_temp_limit( uint8_t dxl_id, int val );
65  void set_param_vol_limit( uint8_t dxl_id, int max, int min );
66  void set_param_current_limit( uint8_t dxl_id, int val );
67  void set_param_vel_gain( uint8_t dxl_id, int p, int i );
68  void set_param_pos_gain_all( int p, int i, int d );
69  void set_param_pos_gain( uint8_t dxl_id, int p, int i, int d );
70 
71  bool is_change_positions( void );
72  void lock_port( void ){ dev_mtx->lock(); }
73  void unlock_port( void ){ dev_mtx->unlock(); }
74  std::string::size_type get_error( std::string& errorlog );
75  bool setup_indirect( uint8_t dxl_id );
76 
77  uint32_t tempCount;
78  std::vector<JOINT_CONTROL> joints;
79 
80 private:
81  uint8_t joint_num;
82  bool port_stat;
93 
94  bool init_stat;
95  uint32_t rx_err;
96  uint32_t tx_err;
98 
100  std::queue<std::string> error_queue;
101 
102  bool check_servo_param( uint8_t dxl_id, uint32_t test_addr, uint8_t equal, uint8_t& read_val );
103  bool check_servo_param( uint8_t dxl_id, uint32_t test_addr, uint16_t equal, uint16_t& read_val );
104  bool check_servo_param( uint8_t dxl_id, uint32_t test_addr, uint32_t equal, uint32_t& read_val );
105 };
106 
107 #endif /* DXLPORT_CONTROL_H */
DXLPORT_CONTROL::get_error
std::string::size_type get_error(std::string &errorlog)
Definition: dxlport_control.cpp:1128
DXLPORT_CONTROL::set_param_drive_mode
void set_param_drive_mode(uint8_t dxl_id, int val)
Definition: dxlport_control.cpp:795
DXLPORT_CONTROL::~DXLPORT_CONTROL
~DXLPORT_CONTROL()
Definition: dxlport_control.cpp:145
DXLPORT_CONTROL::get_joint_num
uint8_t get_joint_num(void)
Definition: dxlport_control.h:55
DXLPORT_CONTROL::joints
std::vector< JOINT_CONTROL > joints
Definition: dxlport_control.h:78
DXLPORT_CONTROL::set_param_pos_gain_all
void set_param_pos_gain_all(int p, int i, int d)
Definition: dxlport_control.cpp:1058
DXLPORT_CONTROL::set_param_ope_mode
void set_param_ope_mode(uint8_t dxl_id, int val)
Definition: dxlport_control.cpp:824
HOME_MOTION_DATA::start
uint16_t start
Definition: dxlport_control.h:23
hardware_interface::JointStateInterface
DXLPORT_CONTROL::DXLPORT_CONTROL
DXLPORT_CONTROL(ros::NodeHandle handle, CONTROL_SETTING &setting)
Definition: dxlport_control.cpp:15
ros.h
dynamixel::GroupBulkRead
HOME_MOTION_DATA::step
uint16_t step
Definition: dxlport_control.h:25
DXLPORT_CONTROL::set_param_home_offset
void set_param_home_offset(uint8_t dxl_id, int val)
Definition: dxlport_control.cpp:853
dynamixel::GroupBulkWrite
DXLPORT_CONTROL::readPos
bool readPos(ros::Time, ros::Duration)
Definition: dxlport_control.cpp:201
DEVICE_MUTEX::unlock
void unlock()
Definition: device_mutex.h:89
DXLPORT_CONTROL::set_torque
bool set_torque(uint8_t dxl_id, bool torque)
Definition: dxlport_control.cpp:430
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:82
HOME_MOTION_DATA::home_rad
double home_rad
Definition: dxlport_control.h:22
DXLPORT_CONTROL::is_change_positions
bool is_change_positions(void)
Definition: dxlport_control.cpp:359
DXLPORT_CONTROL
Definition: dxlport_control.h:31
DXLPORT_CONTROL::readCurrent
bool readCurrent(ros::Time, ros::Duration)
Definition: dxlport_control.cpp:223
DXLPORT_CONTROL::init_stat
bool init_stat
Definition: dxlport_control.h:94
DXLPORT_CONTROL::readVel
bool readVel(ros::Time, ros::Duration)
Definition: dxlport_control.cpp:266
DXLPORT_CONTROL::startup_motion
void startup_motion(void)
Definition: dxlport_control.cpp:490
DXLPORT_CONTROL::readIndirectGroup
dynamixel::GroupBulkRead * readIndirectGroup
Definition: dxlport_control.h:90
DXLPORT_CONTROL::joint_num
uint8_t joint_num
Definition: dxlport_control.h:81
DXLPORT_CONTROL::dev_mtx
DEVICE_MUTEX * dev_mtx
Definition: dxlport_control.h:99
DXLPORT_CONTROL::error_queue
std::queue< std::string > error_queue
Definition: dxlport_control.h:100
DXLPORT_CONTROL::set_param_vol_limit
void set_param_vol_limit(uint8_t dxl_id, int max, int min)
Definition: dxlport_control.cpp:940
dynamixel::PortHandler
DXLPORT_CONTROL::get_init_stat
bool get_init_stat(void)
Definition: dxlport_control.h:54
joint_command_interface.h
hardware_interface::RobotHW
DXLPORT_CONTROL::set_torque_all
void set_torque_all(bool torque)
Definition: dxlport_control.cpp:454
DXLPORT_CONTROL::joint_stat_if
hardware_interface::JointStateInterface joint_stat_if
Definition: dxlport_control.h:85
HOME_MOTION_DATA
Definition: dxlport_control.h:20
DXLPORT_CONTROL::getDuration
ros::Duration getDuration(ros::Time t) const
Definition: dxlport_control.h:37
control_setting.h
DXLPORT_CONTROL::write
void write(ros::Time, ros::Duration)
Definition: dxlport_control.cpp:285
DXLPORT_CONTROL::readTempGroup
dynamixel::GroupBulkRead * readTempGroup
Definition: dxlport_control.h:89
hardware_interface::EffortJointInterface
DXLPORT_CONTROL::set_param_moving_threshold
void set_param_moving_threshold(uint8_t dxl_id, int val)
Definition: dxlport_control.cpp:882
DEVICE_MUTEX::lock
void lock()
Definition: device_mutex.h:83
DXLPORT_CONTROL::init_joint_params
void init_joint_params(ST_JOINT_PARAM &param, int table_id, int value)
Definition: dxlport_control.cpp:633
DXLPORT_CONTROL::read
bool read(ros::Time, ros::Duration)
Definition: dxlport_control.cpp:156
DXLPORT_CONTROL::set_goal_current_all
void set_goal_current_all(uint16_t current)
Definition: dxlport_control.cpp:401
DXLPORT_CONTROL::tempTime
ros::Time tempTime
Definition: dxlport_control.h:97
DEVICE_MUTEX
Definition: device_mutex.h:19
DXLPORT_CONTROL::rx_err
uint32_t rx_err
Definition: dxlport_control.h:95
DXLPORT_CONTROL::set_param_vel_gain
void set_param_vel_gain(uint8_t dxl_id, int p, int i)
Definition: dxlport_control.cpp:1013
device_mutex.h
DXLPORT_CONTROL::unlock_port
void unlock_port(void)
Definition: dxlport_control.h:73
DXLPORT_CONTROL::writeGoalGroup
dynamixel::GroupBulkWrite * writeGoalGroup
Definition: dxlport_control.h:91
DXLPORT_CONTROL::getTime
ros::Time getTime() const
Definition: dxlport_control.h:36
DXLPORT_CONTROL::lock_port
void lock_port(void)
Definition: dxlport_control.h:72
DXLPORT_CONTROL::set_gain
void set_gain(uint8_t dxl_id, uint16_t gain)
Definition: dxlport_control.cpp:385
joint_state_interface.h
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:372
DXLPORT_CONTROL::readTemp
bool readTemp(ros::Time, ros::Duration)
Definition: dxlport_control.cpp:245
DXLPORT_CONTROL::set_param_delay_time
void set_param_delay_time(uint8_t dxl_id, int val)
Definition: dxlport_control.cpp:766
DXLPORT_CONTROL::packetHandler
dynamixel::PacketHandler * packetHandler
Definition: dxlport_control.h:83
DXLPORT_CONTROL::joint_pos_if
hardware_interface::PositionJointInterface joint_pos_if
Definition: dxlport_control.h:86
joint_limits_interface::PositionJointSoftLimitsInterface
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:566
DXLPORT_CONTROL::set_param_current_limit
void set_param_current_limit(uint8_t dxl_id, int val)
Definition: dxlport_control.cpp:984
DXLPORT_CONTROL::set_param_temp_limit
void set_param_temp_limit(uint8_t dxl_id, int val)
Definition: dxlport_control.cpp:911
DXLPORT_CONTROL::tx_err
uint32_t tx_err
Definition: dxlport_control.h:96
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:1068
DXLPORT_CONTROL::portHandler
dynamixel::PortHandler * portHandler
Definition: dxlport_control.h:84
robot_hw.h
dynamixel_sdk.h
DXLPORT_CONTROL::joint_limits_if
joint_limits_interface::PositionJointSoftLimitsInterface joint_limits_if
Definition: dxlport_control.h:88
DXLPORT_CONTROL::writePosGoalGroup
dynamixel::GroupBulkWrite * writePosGoalGroup
Definition: dxlport_control.h:92
DXLPORT_CONTROL::joint_eff_if
hardware_interface::EffortJointInterface joint_eff_if
Definition: dxlport_control.h:87
DXLPORT_CONTROL::set_watchdog
void set_watchdog(uint8_t dxl_id, uint8_t value)
Definition: dxlport_control.cpp:463
DXLPORT_CONTROL::self_check
std::string self_check(void)
Definition: dxlport_control.cpp:694
DXLPORT_CONTROL::set_watchdog_all
void set_watchdog_all(uint8_t value)
Definition: dxlport_control.cpp:482
HOME_MOTION_DATA::start_rad
double start_rad
Definition: dxlport_control.h:24
DXLPORT_CONTROL::setup_indirect
bool setup_indirect(uint8_t dxl_id)
Definition: dxlport_control.cpp:1138
hardware_interface::PositionJointInterface
DXLPORT_CONTROL::tempCount
uint32_t tempCount
Definition: dxlport_control.h:77
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:414
ros::NodeHandle
HOME_MOTION_DATA::home
uint16_t home
Definition: dxlport_control.h:21
DXLPORT_CONTROL::readId
bool readId(ros::Time, ros::Duration)
Definition: dxlport_control.cpp:177
HOME_MOTION_DATA::step_rad
double step_rad
Definition: dxlport_control.h:26
ros::Time::now
static Time now()


sciurus17_control
Author(s): Hiroyuki Nomura
autogenerated on Fri Aug 2 2024 08:37:24