- added velocity p/i/d gain and position i/d gain sync_write code.
This commit is contained in:
@@ -19,6 +19,9 @@ goal_current_item_name = goal_torque
|
||||
position_d_gain_item_name =
|
||||
position_i_gain_item_name =
|
||||
position_p_gain_item_name = position_p_gain
|
||||
velocity_d_gain_item_name =
|
||||
velocity_i_gain_item_name = velocity_i_gain
|
||||
velocity_p_gain_item_name = velocity_p_gain
|
||||
|
||||
[control table]
|
||||
# addr | item name | length | access | memory | min value | max value | signed
|
||||
|
@@ -21,6 +21,9 @@ goal_current_item_name = goal_torque
|
||||
position_d_gain_item_name =
|
||||
position_i_gain_item_name =
|
||||
position_p_gain_item_name = position_p_gain
|
||||
velocity_d_gain_item_name =
|
||||
velocity_i_gain_item_name = velocity_i_gain
|
||||
velocity_p_gain_item_name = velocity_p_gain
|
||||
|
||||
[control table]
|
||||
# addr | item name | length | access | memory | min value | max value | signed
|
||||
|
@@ -21,6 +21,9 @@ goal_current_item_name = goal_torque
|
||||
position_d_gain_item_name =
|
||||
position_i_gain_item_name =
|
||||
position_p_gain_item_name = position_p_gain
|
||||
velocity_d_gain_item_name =
|
||||
velocity_i_gain_item_name = velocity_i_gain
|
||||
velocity_p_gain_item_name = velocity_p_gain
|
||||
|
||||
[control table]
|
||||
# addr | item name | length | access | memory | min value | max value | signed
|
||||
|
@@ -21,6 +21,9 @@ goal_current_item_name = goal_torque
|
||||
position_d_gain_item_name =
|
||||
position_i_gain_item_name =
|
||||
position_p_gain_item_name = position_p_gain
|
||||
velocity_d_gain_item_name =
|
||||
velocity_i_gain_item_name = velocity_i_gain
|
||||
velocity_p_gain_item_name = velocity_p_gain
|
||||
|
||||
[control table]
|
||||
# addr | item name | length | access | memory | min value | max value | signed
|
||||
|
@@ -21,6 +21,9 @@ goal_current_item_name = goal_torque
|
||||
position_d_gain_item_name =
|
||||
position_i_gain_item_name =
|
||||
position_p_gain_item_name = position_p_gain
|
||||
velocity_d_gain_item_name =
|
||||
velocity_i_gain_item_name = velocity_i_gain
|
||||
velocity_p_gain_item_name = velocity_p_gain
|
||||
|
||||
[control table]
|
||||
# addr | item name | length | access | memory | min value | max value | signed
|
||||
|
@@ -19,6 +19,9 @@ goal_current_item_name = goal_torque
|
||||
position_d_gain_item_name =
|
||||
position_i_gain_item_name =
|
||||
position_p_gain_item_name = position_p_gain
|
||||
velocity_d_gain_item_name =
|
||||
velocity_i_gain_item_name = velocity_i_gain
|
||||
velocity_p_gain_item_name = velocity_p_gain
|
||||
|
||||
[control table]
|
||||
# addr | item name | length | access | memory | min value | max value | signed
|
||||
|
@@ -19,6 +19,9 @@ goal_current_item_name = goal_torque
|
||||
position_d_gain_item_name =
|
||||
position_i_gain_item_name =
|
||||
position_p_gain_item_name = position_p_gain
|
||||
velocity_d_gain_item_name =
|
||||
velocity_i_gain_item_name = velocity_i_gain
|
||||
velocity_p_gain_item_name = velocity_p_gain
|
||||
|
||||
[control table]
|
||||
# addr | item name | length | access | memory | min value | max value | signed
|
||||
|
@@ -19,6 +19,9 @@ goal_current_item_name = goal_torque
|
||||
position_d_gain_item_name =
|
||||
position_i_gain_item_name =
|
||||
position_p_gain_item_name = position_p_gain
|
||||
velocity_d_gain_item_name =
|
||||
velocity_i_gain_item_name = velocity_i_gain
|
||||
velocity_p_gain_item_name = velocity_p_gain
|
||||
|
||||
[control table]
|
||||
# addr | item name | length | access | memory | min value | max value | signed
|
||||
|
@@ -19,6 +19,9 @@ goal_current_item_name = goal_torque
|
||||
position_d_gain_item_name =
|
||||
position_i_gain_item_name =
|
||||
position_p_gain_item_name = position_p_gain
|
||||
velocity_d_gain_item_name =
|
||||
velocity_i_gain_item_name = velocity_i_gain
|
||||
velocity_p_gain_item_name = velocity_p_gain
|
||||
|
||||
[control table]
|
||||
# addr | item name | length | access | memory | min value | max value | signed
|
||||
|
@@ -19,6 +19,9 @@ goal_current_item_name = goal_torque
|
||||
position_d_gain_item_name =
|
||||
position_i_gain_item_name =
|
||||
position_p_gain_item_name = position_p_gain
|
||||
velocity_d_gain_item_name =
|
||||
velocity_i_gain_item_name = velocity_i_gain
|
||||
velocity_p_gain_item_name = velocity_p_gain
|
||||
|
||||
[control table]
|
||||
# addr | item name | length | access | memory | min value | max value | signed
|
||||
|
@@ -19,6 +19,9 @@ goal_current_item_name = goal_torque
|
||||
position_d_gain_item_name =
|
||||
position_i_gain_item_name =
|
||||
position_p_gain_item_name = position_p_gain
|
||||
velocity_d_gain_item_name =
|
||||
velocity_i_gain_item_name = velocity_i_gain
|
||||
velocity_p_gain_item_name = velocity_p_gain
|
||||
|
||||
[control table]
|
||||
# addr | item name | length | access | memory | min value | max value | signed
|
||||
|
@@ -19,6 +19,9 @@ goal_current_item_name = goal_torque
|
||||
position_d_gain_item_name =
|
||||
position_i_gain_item_name =
|
||||
position_p_gain_item_name = position_p_gain
|
||||
velocity_d_gain_item_name =
|
||||
velocity_i_gain_item_name = velocity_i_gain
|
||||
velocity_p_gain_item_name = velocity_p_gain
|
||||
|
||||
[control table]
|
||||
# addr | item name | length | access | memory | min value | max value | signed
|
||||
|
@@ -19,6 +19,9 @@ goal_current_item_name = goal_torque
|
||||
position_d_gain_item_name =
|
||||
position_i_gain_item_name =
|
||||
position_p_gain_item_name = position_p_gain
|
||||
velocity_d_gain_item_name =
|
||||
velocity_i_gain_item_name = velocity_i_gain
|
||||
velocity_p_gain_item_name = velocity_p_gain
|
||||
|
||||
[control table]
|
||||
# addr | item name | length | access | memory | min value | max value | signed
|
||||
|
@@ -19,6 +19,9 @@ goal_current_item_name =
|
||||
position_d_gain_item_name = position_d_gain
|
||||
position_i_gain_item_name = position_i_gain
|
||||
position_p_gain_item_name = position_p_gain
|
||||
velocity_d_gain_item_name =
|
||||
velocity_i_gain_item_name =
|
||||
velocity_p_gain_item_name =
|
||||
|
||||
[control table]
|
||||
# addr | item name | length | access | memory | min value | max value | signed
|
||||
|
@@ -19,6 +19,9 @@ goal_current_item_name =
|
||||
position_d_gain_item_name = position_d_gain
|
||||
position_i_gain_item_name = position_i_gain
|
||||
position_p_gain_item_name = position_p_gain
|
||||
velocity_d_gain_item_name =
|
||||
velocity_i_gain_item_name =
|
||||
velocity_p_gain_item_name =
|
||||
|
||||
[control table]
|
||||
# addr | item name | length | access | memory | min value | max value | signed
|
||||
|
@@ -19,6 +19,9 @@ goal_current_item_name =
|
||||
position_d_gain_item_name = position_d_gain
|
||||
position_i_gain_item_name = position_i_gain
|
||||
position_p_gain_item_name = position_p_gain
|
||||
velocity_d_gain_item_name =
|
||||
velocity_i_gain_item_name =
|
||||
velocity_p_gain_item_name =
|
||||
|
||||
[control table]
|
||||
# addr | item name | length | access | memory | min value | max value | signed
|
||||
|
@@ -22,6 +22,9 @@ goal_current_item_name = goal_current
|
||||
position_d_gain_item_name = position_d_gain
|
||||
position_i_gain_item_name = position_i_gain
|
||||
position_p_gain_item_name = position_p_gain
|
||||
velocity_d_gain_item_name =
|
||||
velocity_i_gain_item_name = velocity_i_gain
|
||||
velocity_p_gain_item_name = velocity_p_gain
|
||||
|
||||
[control table]
|
||||
# addr | item name | length | access | memory | min value | max value | signed
|
||||
|
@@ -22,6 +22,9 @@ goal_current_item_name = goal_current
|
||||
position_d_gain_item_name = position_d_gain
|
||||
position_i_gain_item_name = position_i_gain
|
||||
position_p_gain_item_name = position_p_gain
|
||||
velocity_d_gain_item_name =
|
||||
velocity_i_gain_item_name = velocity_i_gain
|
||||
velocity_p_gain_item_name = velocity_p_gain
|
||||
|
||||
[control table]
|
||||
# addr | item name | length | access | memory | min value | max value | signed
|
||||
|
@@ -21,6 +21,9 @@ goal_current_item_name = goal_current
|
||||
position_d_gain_item_name = position_d_gain
|
||||
position_i_gain_item_name = position_i_gain
|
||||
position_p_gain_item_name = position_p_gain
|
||||
velocity_d_gain_item_name =
|
||||
velocity_i_gain_item_name = velocity_i_gain
|
||||
velocity_p_gain_item_name = velocity_p_gain
|
||||
|
||||
[control table]
|
||||
# addr | item name | length | access | memory | min value | max value | signed
|
||||
|
@@ -73,6 +73,11 @@ public:
|
||||
ControlTableItem *goal_velocity_item_;
|
||||
ControlTableItem *goal_current_item_;
|
||||
ControlTableItem *position_p_gain_item_;
|
||||
ControlTableItem *position_i_gain_item_;
|
||||
ControlTableItem *position_d_gain_item_;
|
||||
ControlTableItem *velocity_p_gain_item_;
|
||||
ControlTableItem *velocity_i_gain_item_;
|
||||
ControlTableItem *velocity_d_gain_item_;
|
||||
|
||||
Dynamixel(int id, std::string model_name, float protocol_version);
|
||||
|
||||
|
@@ -60,6 +60,11 @@ public:
|
||||
double goal_velocity_;
|
||||
double goal_torque_;
|
||||
double position_p_gain_;
|
||||
double position_i_gain_;
|
||||
double position_d_gain_;
|
||||
double velocity_p_gain_;
|
||||
double velocity_i_gain_;
|
||||
double velocity_d_gain_;
|
||||
|
||||
std::map<std::string, uint32_t> bulk_read_table_;
|
||||
|
||||
@@ -74,6 +79,11 @@ public:
|
||||
goal_velocity_(0.0),
|
||||
goal_torque_(0.0),
|
||||
position_p_gain_(0.0),
|
||||
position_i_gain_(0.0),
|
||||
position_d_gain_(0.0),
|
||||
velocity_p_gain_(0.0),
|
||||
velocity_i_gain_(0.0),
|
||||
velocity_d_gain_(0.0),
|
||||
position_offset_(0.0)
|
||||
{
|
||||
bulk_read_table_.clear();
|
||||
|
@@ -55,7 +55,12 @@ Dynamixel::Dynamixel(int id, std::string model_name, float protocol_version)
|
||||
goal_position_item_(0),
|
||||
goal_velocity_item_(0),
|
||||
goal_current_item_(0),
|
||||
position_p_gain_item_(0)
|
||||
position_p_gain_item_(0),
|
||||
position_i_gain_item_(0),
|
||||
position_d_gain_item_(0),
|
||||
velocity_p_gain_item_(0),
|
||||
velocity_i_gain_item_(0),
|
||||
velocity_d_gain_item_(0)
|
||||
{
|
||||
this->id_ = id;
|
||||
this->model_name_ = model_name;
|
||||
|
Reference in New Issue
Block a user