Skip to content

Commit

Permalink
AP_DDS: Rally point message simplified
Browse files Browse the repository at this point in the history
  • Loading branch information
tizianofiorenzani committed Nov 5, 2024
1 parent 5fe69ef commit 0c549f9
Show file tree
Hide file tree
Showing 4 changed files with 1 addition and 37 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -40,9 +40,6 @@
RALLY_0.point.latitude =-35.0
RALLY_0.point.longitude = 149.0
RALLY_0.point.altitude = 400.0
RALLY_0.break_altitude = 300.0
RALLY_0.land_dir = 20.0
RALLY_0.break_altitude = 20.0
RALLY_0.altitude_frame = 2


Expand Down Expand Up @@ -131,7 +128,6 @@ def process_compare(self, rally):
print (f"{response.rally.point.latitude} - {rally.point.latitude}")
if (abs(response.rally.point.latitude - rally.point.latitude) < 1e-7
and abs(response.rally.point.longitude - rally.point.longitude) < 1e-7
and response.rally.break_altitude == rally.break_altitude
and response.rally.altitude_frame == rally.altitude_frame):
self.get_rally_event.set()
return
Expand Down
8 changes: 0 additions & 8 deletions Tools/ros2/ardupilot_msgs/msg/Rally.msg
Original file line number Diff line number Diff line change
@@ -1,12 +1,4 @@
geographic_msgs/GeoPoint point
float32 break_altitude # when autolanding, break out of loiter at this alt relative to Home (meters)
float32 land_dir # Heading to aim for when landing (degrees)

# seek favorable winds when choosing a landing poi
bool flag_favorable_winds

# do auto land after arriving
bool flag_do_auto_land

# Altitude reference frame
uint8 ALTITUDE_FRAME_ABSOLUTE = 0
Expand Down
10 changes: 1 addition & 9 deletions libraries/AP_DDS/AP_DDS_Client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -826,10 +826,6 @@ void AP_DDS_Client::on_request(uxrSession* uxr_session, uxrObjectId object_id, u
rally_get_response.rally.point.latitude = rally_location.lat * 1e-7;
rally_get_response.rally.point.longitude = rally_location.lng * 1e-7;
rally_get_response.rally.point.altitude = rally_location.alt;
rally_get_response.rally.break_altitude = rally_location.break_alt;
rally_get_response.rally.land_dir = rally_location.land_dir * 1e-2f;
rally_get_response.rally.flag_favorable_winds = rally_location.flags & (1 << 0);
rally_get_response.rally.flag_do_auto_land = rally_location.flags & (1 << 1);
bool alt_frame_valid = rally_location.flags & (1 << 2);
if (alt_frame_valid) {
rally_get_response.rally.altitude_frame = (rally_location.flags >> 3) & ((1 << 2) - 1);
Expand All @@ -840,7 +836,7 @@ void AP_DDS_Client::on_request(uxrSession* uxr_session, uxrObjectId object_id, u
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Request Rally index %u is valid: lat: %f lon: %f",
msg_prefix, rally_get_request.index, rally_get_response.rally.point.latitude, rally_get_response.rally.point.longitude);
} else {
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Request Rally index %u is invalid", msg_prefix, rally_get_request.index);
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "%s Request Rally index %u is invalid", msg_prefix, rally_get_request.index);
rally_get_response.success = false;
}

Expand Down Expand Up @@ -884,11 +880,7 @@ void AP_DDS_Client::on_request(uxrSession* uxr_session, uxrObjectId object_id, u
rally_location.lat = static_cast<int32_t>(rally_set_request.rally.point.latitude * 1e7);
rally_location.lng = static_cast<int32_t>(rally_set_request.rally.point.longitude * 1e7);
rally_location.alt = static_cast<int16_t>(rally_set_request.rally.point.altitude);
rally_location.break_alt = static_cast<int16_t>(rally_set_request.rally.break_altitude);
rally_location.land_dir = static_cast<int16_t>(rally_set_request.rally.land_dir * 1e2f);
rally_location.flags = 0;
rally_location.flags |= ((rally_set_request.rally.flag_favorable_winds ? 1 : 0) << 0);
rally_location.flags |= ((rally_set_request.rally.flag_do_auto_land ? 1 : 0) << 1);
rally_location.flags |= (1 << 2); // Use the provided frame.
rally_location.flags |= (rally_set_request.rally.altitude_frame << 3);

Expand Down
16 changes: 0 additions & 16 deletions libraries/AP_DDS/Idl/ardupilot_msgs/msg/Rally.idl
Original file line number Diff line number Diff line change
Expand Up @@ -17,22 +17,6 @@ module ardupilot_msgs {
struct Rally {
geographic_msgs::msg::GeoPoint point;

@verbatim (language="comment", text=
"when autolanding, break out of loiter at this alt relative to Home (meters)")
float break_altitude;

@verbatim (language="comment", text=
"Heading to aim for when landing (degrees)")
float land_dir;

@verbatim (language="comment", text=
"seek favorable winds when choosing a landing poi")
boolean flag_favorable_winds;

@verbatim (language="comment", text=
"do auto land after arriving")
boolean flag_do_auto_land;

uint8 altitude_frame;
};
};
Expand Down

0 comments on commit 0c549f9

Please sign in to comment.