Skip to content

Commit

Permalink
Tools: Optionally include AP_SIM_GLIDER_ENABLED on SIH
Browse files Browse the repository at this point in the history
  • Loading branch information
Georacer committed Jul 18, 2024
1 parent 0901ae7 commit ac5101d
Show file tree
Hide file tree
Showing 3 changed files with 6 additions and 4 deletions.
2 changes: 2 additions & 0 deletions Tools/scripts/sitl-on-hardware/sitl-on-hw.py
Original file line number Diff line number Diff line change
Expand Up @@ -66,6 +66,8 @@ def sohw_path(fname):
defaults_write(open(args.defaults,"r").read() + "\n")

if args.simclass:
if args.simclass == 'Glider':
hwdef_write("define AP_SIM_GLIDER_ENABLED 1\n")
hwdef_write("define AP_SIM_FRAME_CLASS %s\n" % args.simclass)
if args.frame:
hwdef_write('define AP_SIM_FRAME_STRING "%s"\n' % args.frame)
Expand Down
2 changes: 1 addition & 1 deletion libraries/SITL/SIM_Aircraft.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -181,7 +181,7 @@ void Aircraft::update_position(void)
uint32_t now = AP_HAL::millis();
if (now - last_one_hz_ms >= 1000) {
// shift origin of position at 1Hz to current location
// this prevents sperical errors building up in the GPS data
// this prevents spherical errors building up in the GPS data
last_one_hz_ms = now;
Vector2d diffNE = origin.get_distance_NE_double(location);
position.xy() -= diffNE;
Expand Down
6 changes: 3 additions & 3 deletions libraries/SITL/SIM_Glider.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -231,7 +231,7 @@ void Glider::calculate_forces(const struct sitl_input &input, Vector3f &rot_acce
float aileron = 0.5*(filtered_servo_angle(input, 1) + filtered_servo_angle(input, 4));
float elevator = filtered_servo_angle(input, 2);
float rudder = filtered_servo_angle(input, 3);
float balloon = filtered_servo_range(input, 5);
float balloon = MAX(0.0f, filtered_servo_range(input, 5)); // Don't let the balloon receive downwards commands.
float balloon_cut = filtered_servo_range(input, 9);

// Move balloon upwards using balloon velocity from channel 6
Expand All @@ -241,7 +241,7 @@ void Glider::calculate_forces(const struct sitl_input &input, Vector3f &rot_acce
balloon_velocity = Vector3f(-wind_ef.x, -wind_ef.y, -wind_ef.z -balloon_rate * balloon);
balloon_position += balloon_velocity * (1.0e-6 * (float)frame_time_us);
const float height_AMSL = 0.01f * (float)home.alt - position.z;
// release at burst height or when channel 9 goes high
// release at burst height or when baloon cut output goes high
if (hal.scheduler->is_system_initialized() &&
(height_AMSL > balloon_burst_amsl || balloon_cut > 0.8)) {
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "pre-release at %i m AMSL\n", (int)height_AMSL);
Expand Down Expand Up @@ -380,7 +380,7 @@ bool Glider::update_balloon(float balloon, Vector3f &force, Vector3f &rot_accel)
// NED unit vector pointing from tether attachment on plane to attachment on balloon
Vector3f tether_unit_vec_ef = relative_position.normalized();

// NED velocity of attahment point on plane
// NED velocity of attachment point on plane
Vector3f attachment_velocity_ef = velocity_ef + dcm * (gyro % tether_pos_bf);

// NED velocity of attachment point on balloon as seen by observer on attachemnt point on plane
Expand Down

0 comments on commit ac5101d

Please sign in to comment.