Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

SITL: add Omni3Mecanum vehicle to SIM_Rover #27581

Merged
merged 2 commits into from
Jul 23, 2024

Conversation

srmainwaring
Copy link
Contributor

@srmainwaring srmainwaring commented Jul 17, 2024

Add an Omni3 Mecanum vehicle to SIM_Rover

Partially completes #11782

Details

  • Add new frame type rover-omni3mecanum to sim_vehicle.
  • Add matching param file.
  • Add omni3 specific member variables to SIM_Rover
  • Implement dynamics update for the omni3 rover.
  • Split update method into parts that are frame specific and a part common to all frames.

Note the dynamics in SIM_Rover is not an independent test of the Omni3Mecanum mixer as it uses the same kinematics calculation for mapping body motion to wheel angular velocities.

Testing

Run SITL with the new frame type

sim_vehicle.py --debug -v Rover -f rover-omni3mecanum --enable-dds --console --map

Move the rover in MANUAL mode using the RC override commands:

  • yaw right: rc 1 1550, yaw left: rc 1 1450

omni_sitl_yaw

  • move forward: rc 3 1600, move back: rc 3 1400

omni_sitl_fwd

  • move right: rc 4 1600, move left: rc 4 1400

omni_sitl_right

Copy link
Member

@IamPete1 IamPete1 left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

LGTM, thanks.

CRUISE_THROTTLE 42.0
FRAME_TYPE 4
PSC_VEL_P 0.500000
RC1_MAX 2000
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Hi @srmainwaring, thanks for this. Normally we don't add items to the param file that are the same as the defaults. I suspect we don't need these RCx_MIN/MAX values nor the SERVOx_MIN/TRIM/MAX

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thanks @rmackay9, updated in 0044bb5. All remaining params are different from defaults or not set in rover.param.

@srmainwaring srmainwaring force-pushed the prs/pr-sim-rover-omni branch from ad8d640 to 0044bb5 Compare July 20, 2024 10:06
- Add frame rover-omni3mecanum.
- Remove params with default values.

Signed-off-by: Rhys Mainwaring <[email protected]>
@srmainwaring srmainwaring force-pushed the prs/pr-sim-rover-omni branch from 0044bb5 to 97a608b Compare July 20, 2024 21:24
@peterbarker peterbarker merged commit 4354072 into ArduPilot:master Jul 23, 2024
93 checks passed
@peterbarker
Copy link
Contributor

Merged, thjanks!

@srmainwaring srmainwaring deleted the prs/pr-sim-rover-omni branch July 23, 2024 12:10
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging this pull request may close these issues.

4 participants