diff --git a/Gazebo/models/blueboat/model.config b/Gazebo/models/blueboat/model.config index 343a67cb..8420ef08 100644 --- a/Gazebo/models/blueboat/model.config +++ b/Gazebo/models/blueboat/model.config @@ -15,5 +15,23 @@ 3D Models retrieved from: https://cad.bluerobotics.com/BLUEBOAT_120_BR-101447_RevA_PUB.zip + + Properties + + Max speed (unloaded): 3 m/s + - Set thrust multiplier to 70 in ArduPilotPlugin (+/- 35 N) + + ArduPilot + + Vehicle type: Rover + Frame type: rover-skid + + ArduPilot Parameters + + CRUISE_SPEED 2.0 + CRUISE_THROTTLE 50.0 + FRAME_CLASS 2.0 + WP_SPEED 2.0 + diff --git a/Gazebo/models/blueboat/model.sdf b/Gazebo/models/blueboat/model.sdf index 4e9b8575..6fe1d572 100644 --- a/Gazebo/models/blueboat/model.sdf +++ b/Gazebo/models/blueboat/model.sdf @@ -411,7 +411,7 @@ --> motor_port_joint - 10 + 70 -0.5 1000 2000 @@ -428,7 +428,7 @@ --> motor_stbd_joint - 10 + 70 -0.5 1000 2000