AP_DDS: treat goal publisher relying on get_target_location as external control

Signed-off-by: Ryan Friedman <25047695+Ryanf55@users.noreply.github.com>
This commit is contained in:
Ryan Friedman 2025-01-05 16:49:11 -07:00 committed by Peter Barker
parent ceb75dce6b
commit 4086278394
3 changed files with 14 additions and 14 deletions

View File

@ -68,9 +68,9 @@ static constexpr uint16_t DELAY_AIRSPEED_TOPIC_MS = AP_DDS_DELAY_AIRSPEED_TOPIC_
#if AP_DDS_GEOPOSE_PUB_ENABLED
static constexpr uint16_t DELAY_GEO_POSE_TOPIC_MS = AP_DDS_DELAY_GEO_POSE_TOPIC_MS;
#endif // AP_DDS_GEOPOSE_PUB_ENABLED
#if AP_DDS_GOAL_PUB_ENABLED & AP_SCRIPTING_ENABLED
#if AP_DDS_GOAL_PUB_ENABLED
static constexpr uint16_t DELAY_GOAL_TOPIC_MS = AP_DDS_DELAY_GOAL_TOPIC_MS ;
#endif // AP_DDS_GOAL_PUB_ENABLED & AP_SCRIPTING_ENABLED
#endif // AP_DDS_GOAL_PUB_ENABLED
#if AP_DDS_CLOCK_PUB_ENABLED
static constexpr uint16_t DELAY_CLOCK_TOPIC_MS =AP_DDS_DELAY_CLOCK_TOPIC_MS;
#endif // AP_DDS_CLOCK_PUB_ENABLED
@ -567,7 +567,7 @@ void AP_DDS_Client::update_topic(geographic_msgs_msg_GeoPoseStamped& msg)
}
#endif // AP_DDS_GEOPOSE_PUB_ENABLED
#if AP_DDS_GOAL_PUB_ENABLED & AP_SCRIPTING_ENABLED
#if AP_DDS_GOAL_PUB_ENABLED
bool AP_DDS_Client::update_topic_goal(geographic_msgs_msg_GeoPointStamped& msg)
{
const auto &vehicle = AP::vehicle();
@ -598,7 +598,7 @@ bool AP_DDS_Client::update_topic_goal(geographic_msgs_msg_GeoPointStamped& msg)
return false;
}
}
#endif // AP_DDS_GOAL_PUB_ENABLED & AP_SCRIPTING_ENABLED
#endif // AP_DDS_GOAL_PUB_ENABLED
#if AP_DDS_IMU_PUB_ENABLED
void AP_DDS_Client::update_topic(sensor_msgs_msg_Imu& msg)
@ -1628,7 +1628,7 @@ void AP_DDS_Client::write_gps_global_origin_topic()
}
#endif // AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED
#if AP_DDS_GOAL_PUB_ENABLED & AP_SCRIPTING_ENABLED
#if AP_DDS_GOAL_PUB_ENABLED
void AP_DDS_Client::write_goal_topic()
{
WITH_SEMAPHORE(csem);
@ -1642,7 +1642,7 @@ void AP_DDS_Client::write_goal_topic()
}
}
}
#endif // AP_DDS_GOAL_PUB_ENABLED & AP_SCRIPTING_ENABLED
#endif // AP_DDS_GOAL_PUB_ENABLED
#if AP_DDS_STATUS_PUB_ENABLED
void AP_DDS_Client::write_status_topic()
@ -1740,14 +1740,14 @@ void AP_DDS_Client::update()
write_gps_global_origin_topic();
}
#endif // AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED
#if AP_DDS_GOAL_PUB_ENABLED & AP_SCRIPTING_ENABLED
#if AP_DDS_GOAL_PUB_ENABLED
if (cur_time_ms - last_goal_time_ms > DELAY_GOAL_TOPIC_MS) {
if (update_topic_goal(goal_topic)) {
write_goal_topic();
}
last_goal_time_ms = cur_time_ms;
}
#endif // AP_DDS_GOAL_PUB_ENABLED & AP_SCRIPTING_ENABLED
#endif // AP_DDS_GOAL_PUB_ENABLED
#if AP_DDS_STATUS_PUB_ENABLED
if (cur_time_ms - last_status_check_time_ms > DELAY_STATUS_TOPIC_MS) {
if (update_topic(status_topic)) {

View File

@ -114,7 +114,7 @@ private:
static void update_topic(geographic_msgs_msg_GeoPointStamped& msg);
# endif // AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED
#if AP_DDS_GOAL_PUB_ENABLED & AP_SCRIPTING_ENABLED
#if AP_DDS_GOAL_PUB_ENABLED
geographic_msgs_msg_GeoPointStamped goal_topic;
// The last ms timestamp AP_DDS wrote a goal message
uint64_t last_goal_time_ms;
@ -122,7 +122,7 @@ private:
void write_goal_topic();
bool update_topic_goal(geographic_msgs_msg_GeoPointStamped& msg);
geographic_msgs_msg_GeoPointStamped prev_goal_msg;
#endif // AP_DDS_GOAL_PUB_ENABLED & AP_SCRIPTING_ENABLED
#endif // AP_DDS_GOAL_PUB_ENABLED
#if AP_DDS_GEOPOSE_PUB_ENABLED
geographic_msgs_msg_GeoPoseStamped geo_pose_topic;

View File

@ -42,9 +42,9 @@ enum class TopicIndex: uint8_t {
#if AP_DDS_GEOPOSE_PUB_ENABLED
GEOPOSE_PUB,
#endif // AP_DDS_GEOPOSE_PUB_ENABLED
#if AP_DDS_GOAL_PUB_ENABLED & AP_SCRIPTING_ENABLED
#if AP_DDS_GOAL_PUB_ENABLED
GOAL_PUB,
#endif // AP_DDS_GOAL_PUB_ENABLED & AP_SCRIPTING_ENABLED
#endif // AP_DDS_GOAL_PUB_ENABLED
#if AP_DDS_CLOCK_PUB_ENABLED
CLOCK_PUB,
#endif // AP_DDS_CLOCK_PUB_ENABLED
@ -238,7 +238,7 @@ constexpr struct AP_DDS_Client::Topic_table AP_DDS_Client::topics[] = {
},
},
#endif // AP_DDS_GEOPOSE_PUB_ENABLED
#if AP_DDS_GOAL_PUB_ENABLED & AP_SCRIPTING_ENABLED
#if AP_DDS_GOAL_PUB_ENABLED
{
.topic_id = to_underlying(TopicIndex::GOAL_PUB),
.pub_id = to_underlying(TopicIndex::GOAL_PUB),
@ -255,7 +255,7 @@ constexpr struct AP_DDS_Client::Topic_table AP_DDS_Client::topics[] = {
.depth = 1,
},
},
#endif // AP_DDS_GOAL_PUB_ENABLED & AP_SCRIPTING_ENABLED
#endif // AP_DDS_GOAL_PUB_ENABLED
#if AP_DDS_CLOCK_PUB_ENABLED
{
.topic_id = to_underlying(TopicIndex::CLOCK_PUB),