mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
AP_VisualOdom: POS param range of 5m and 1cm increment
This commit is contained in:
parent
9f3154372d
commit
c9b82aa822
@ -35,18 +35,24 @@ const AP_Param::GroupInfo AP_VisualOdom::var_info[] = {
|
|||||||
// @DisplayName: Visual odometry camera X position offset
|
// @DisplayName: Visual odometry camera X position offset
|
||||||
// @Description: X position of the camera in body frame. Positive X is forward of the origin.
|
// @Description: X position of the camera in body frame. Positive X is forward of the origin.
|
||||||
// @Units: m
|
// @Units: m
|
||||||
|
// @Range: -5 5
|
||||||
|
// @Increment: 0.01
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
|
|
||||||
// @Param: _POS_Y
|
// @Param: _POS_Y
|
||||||
// @DisplayName: Visual odometry camera Y position offset
|
// @DisplayName: Visual odometry camera Y position offset
|
||||||
// @Description: Y position of the camera in body frame. Positive Y is to the right of the origin.
|
// @Description: Y position of the camera in body frame. Positive Y is to the right of the origin.
|
||||||
// @Units: m
|
// @Units: m
|
||||||
|
// @Range: -5 5
|
||||||
|
// @Increment: 0.01
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
|
|
||||||
// @Param: _POS_Z
|
// @Param: _POS_Z
|
||||||
// @DisplayName: Visual odometry camera Z position offset
|
// @DisplayName: Visual odometry camera Z position offset
|
||||||
// @Description: Z position of the camera in body frame. Positive Z is down from the origin.
|
// @Description: Z position of the camera in body frame. Positive Z is down from the origin.
|
||||||
// @Units: m
|
// @Units: m
|
||||||
|
// @Range: -5 5
|
||||||
|
// @Increment: 0.01
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("_POS", 1, AP_VisualOdom, _pos_offset, 0.0f),
|
AP_GROUPINFO("_POS", 1, AP_VisualOdom, _pos_offset, 0.0f),
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user