joint_control.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
2 #include <ros/package.h>
3 #include <angles/angles.h>
5 
6 void JOINT_CONTROL::init_parameter( std::string init_name, uint8_t init_dxlid, uint16_t init_center, uint16_t init_home, double init_eff_const, uint8_t init_mode )
7 {
8  name = init_name;
9  id = init_dxlid;
10  pos = 0.0;
11  vel = 0.0;
12  eff = 0.0;
13  curr = 0.0;
14  torque = false;
15  center = init_center;
16  home = init_home;
17  connect = false;
18 
19  goal_pos = 0.0;
20  goal_vel = 0.0;
21  goal_eff = 0.0;
22 
23  dxl_pos = 0;
24  dxl_curr = 0;
25  dxl_temp = 0;
26  for( int ii=0 ; ii<sizeof(dxl_goal) ; ++ii ){
27  dxl_goal[ii] = 0;
28  }
29  eff_const = init_eff_const;
30  eff_limiting = false;
31  eff_over_cnt = 0;
32 
33  if( init_mode == OPERATING_MODE_CURRENT ){
35  }else if( init_mode == OPERATING_MODE_CURR_POS ){
37  }else{
39  }
40 }
42 {
44 }
45 JOINT_CONTROL::JOINT_CONTROL( std::string init_name, uint8_t init_dxlid, uint16_t init_center, uint16_t init_home, double init_eff_const, uint8_t init_mode )
46 {
47  init_parameter( init_name, init_dxlid, init_center, init_home, init_eff_const, init_mode );
48 }
50 {
51  name = src.name;
52  id = src.id;
53  pos = src.pos;
54  vel = src.vel;
55  eff = src.eff;
56  curr = src.curr;
57  torque = src.torque;
58  center = src.center;
59  home = src.home;
60  connect = src.connect;
61 
62  goal_pos = src.goal_pos;
63  goal_vel = src.goal_vel;
64  goal_eff = src.goal_eff;
65 
66  dxl_pos = src.dxl_pos;
67  dxl_curr = src.dxl_curr;
68  dxl_temp = src.dxl_temp;
69  for( int ii=0 ; ii<sizeof(dxl_goal) ; ++ii ){
70  dxl_goal[ii] = src.dxl_goal[ii];
71  }
72  eff_const = src.eff_const;
75 
76  ope_mode = src.ope_mode;
77 }
78 
JOINT_CONTROL::init_parameter
void init_parameter(std::string init_name, uint8_t init_dxlid, uint16_t init_center, uint16_t init_home, double init_eff_const, uint8_t init_mode)
Definition: joint_control.cpp:6
ros.h
JOINT_CONTROL::goal_eff
double goal_eff
Definition: joint_control.h:287
OPERATING_MODE_POSITION
#define OPERATING_MODE_POSITION
Definition: joint_control.h:196
JOINT_CONTROL
Definition: joint_control.h:203
JOINT_CONTROL::pos
double pos
Definition: joint_control.h:268
joint_control.h
JOINT_CONTROL::eff
double eff
Definition: joint_control.h:270
OPERATING_MODE_CURR_POS
#define OPERATING_MODE_CURR_POS
Definition: joint_control.h:198
JOINT_CONTROL::ope_mode
uint8_t ope_mode
Definition: joint_control.h:283
JOINT_CONTROL::goal_pos
double goal_pos
Definition: joint_control.h:285
JOINT_CONTROL::id
uint8_t id
Definition: joint_control.h:267
DXL_EFFORT_CONST
#define DXL_EFFORT_CONST
Definition: joint_control.h:171
JOINT_CONTROL::dxl_temp
uint8_t dxl_temp
Definition: joint_control.h:291
JOINT_CONTROL::vel
double vel
Definition: joint_control.h:269
OPERATING_MODE_CURRENT
#define OPERATING_MODE_CURRENT
Definition: joint_control.h:194
JOINT_CONTROL::dxl_curr
uint16_t dxl_curr
Definition: joint_control.h:290
JOINT_CONTROL::goal_vel
double goal_vel
Definition: joint_control.h:286
package.h
JOINT_CONTROL::dxl_pos
uint32_t dxl_pos
Definition: joint_control.h:289
JOINT_CONTROL::home
uint16_t home
Definition: joint_control.h:278
JOINT_CONTROL::connect
bool connect
Definition: joint_control.h:279
JOINT_CONTROL::eff_over_cnt
uint8_t eff_over_cnt
Definition: joint_control.h:282
JOINT_CONTROL::eff_const
double eff_const
Definition: joint_control.h:280
JOINT_CONTROL::dxl_goal
uint8_t dxl_goal[4]
Definition: joint_control.h:292
JOINT_CONTROL::center
uint16_t center
Definition: joint_control.h:277
JOINT_CONTROL::name
std::string name
Definition: joint_control.h:266
JOINT_CONTROL::curr
double curr
Definition: joint_control.h:274
JOINT_CONTROL::JOINT_CONTROL
JOINT_CONTROL(void)
Definition: joint_control.cpp:41
JOINT_CONTROL::eff_limiting
bool eff_limiting
Definition: joint_control.h:281
DXL_OFFSET_DEFAULT
#define DXL_OFFSET_DEFAULT
Definition: joint_control.h:179
JOINT_CONTROL::torque
bool torque
Definition: joint_control.h:276
angles.h


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