Rover: add param to offset balancing point for balance bots

This commit is contained in:
Ebin 2018-12-13 13:19:08 +05:30 committed by Randy Mackay
parent 76910f9283
commit e806d0c385
3 changed files with 13 additions and 1 deletions

View File

@ -694,6 +694,15 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
AP_SUBGROUPINFO(gripper, "GRIP_", 39, ParametersG2, AP_Gripper), AP_SUBGROUPINFO(gripper, "GRIP_", 39, ParametersG2, AP_Gripper),
#endif #endif
// @Param: BAL_PITCH_TRIM
// @DisplayName: Balance Bot pitch trim angle
// @Description: Balance Bot pitch trim for balancing. This offsets the tilt of the center of mass.
// @Units: deg
// @Range: -2 2
// @Increment: 0.1
// @User: Standard
AP_GROUPINFO("BAL_PITCH_TRIM", 40, ParametersG2, bal_pitch_trim, 0),
AP_GROUPEND AP_GROUPEND
}; };

View File

@ -396,6 +396,9 @@ public:
// mission behave // mission behave
AP_Int8 mis_done_behave; AP_Int8 mis_done_behave;
// balance both pitch trim
AP_Float bal_pitch_trim;
}; };
extern const AP_Param::Info var_info[]; extern const AP_Param::Info var_info[];

View File

@ -5,7 +5,7 @@
void Rover::balancebot_pitch_control(float &throttle) void Rover::balancebot_pitch_control(float &throttle)
{ {
// calculate desired pitch angle // calculate desired pitch angle
const float demanded_pitch = radians(-throttle * 0.01f * g2.bal_pitch_max); const float demanded_pitch = radians(-throttle * 0.01f * g2.bal_pitch_max) + radians(g2.bal_pitch_trim);
// calculate speed from wheel encoders // calculate speed from wheel encoders
float veh_speed_pct = 0.0f; float veh_speed_pct = 0.0f;