Skip to content

Commit

Permalink
Remove uorb topics exclusively used for avoidance
Browse files Browse the repository at this point in the history
- TrajectoryBezier.msg
- TrajectoryWaypoint.msg
- VehicleTrajectoryBezier.msg
- VehicleTrajectoryWaypoint.msg

Additionally remove TRAJECTORY_REPRESENTATION_WAYPOINTS mavlink stream.

Signed-off-by: Silvan <[email protected]>
  • Loading branch information
sfuhrer committed Jan 10, 2025
1 parent 73962b8 commit 4998fe9
Show file tree
Hide file tree
Showing 14 changed files with 0 additions and 296 deletions.
4 changes: 0 additions & 4 deletions msg/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -210,8 +210,6 @@ set(msg_files
TelemetryStatus.msg
TiltrotorExtraControls.msg
TimesyncStatus.msg
TrajectoryBezier.msg
TrajectoryWaypoint.msg
TransponderReport.msg
TuneControl.msg
UavcanParameterRequest.msg
Expand All @@ -231,8 +229,6 @@ set(msg_files
VehicleRoi.msg
VehicleThrustSetpoint.msg
VehicleTorqueSetpoint.msg
VehicleTrajectoryBezier.msg
VehicleTrajectoryWaypoint.msg
VelocityLimits.msg
WheelEncoders.msg
Wind.msg
Expand Down
8 changes: 0 additions & 8 deletions msg/TrajectoryBezier.msg

This file was deleted.

13 changes: 0 additions & 13 deletions msg/TrajectoryWaypoint.msg

This file was deleted.

18 changes: 0 additions & 18 deletions msg/VehicleTrajectoryBezier.msg

This file was deleted.

21 changes: 0 additions & 21 deletions msg/VehicleTrajectoryWaypoint.msg

This file was deleted.

2 changes: 0 additions & 2 deletions src/modules/logger/logged_topics.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -327,8 +327,6 @@ void LoggedTopics::add_vision_and_avoidance_topics()
add_topic("obstacle_distance_fused");
add_topic("obstacle_distance");
add_topic("vehicle_mocap_odometry", 30);
add_topic("vehicle_trajectory_waypoint", 200);
add_topic("vehicle_trajectory_waypoint_desired", 200);
add_topic("vehicle_visual_odometry", 30);
}

Expand Down
3 changes: 0 additions & 3 deletions src/modules/mavlink/mavlink_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1525,7 +1525,6 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
configure_stream_local("SYS_STATUS", 5.0f);
configure_stream_local("SYSTEM_TIME", 1.0f);
configure_stream_local("TIME_ESTIMATE_TO_TARGET", 1.0f);
configure_stream_local("TRAJECTORY_REPRESENTATION_WAYPOINTS", 5.0f);
configure_stream_local("VFR_HUD", 10.0f);
configure_stream_local("VIBRATION", 0.5f);
configure_stream_local("WIND_COV", 10.0f);
Expand Down Expand Up @@ -1592,7 +1591,6 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
configure_stream_local("RC_CHANNELS", 5.0f);
configure_stream_local("SERVO_OUTPUT_RAW_0", 1.0f);
configure_stream_local("SYS_STATUS", 5.0f);
configure_stream_local("TRAJECTORY_REPRESENTATION_WAYPOINTS", 5.0f);
configure_stream_local("VFR_HUD", 4.0f);
configure_stream_local("VIBRATION", 0.5f);
configure_stream_local("WIND_COV", 1.0f);
Expand Down Expand Up @@ -1783,7 +1781,6 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
configure_stream_local("SYS_STATUS", 5.0f);
configure_stream_local("SYSTEM_TIME", 2.0f);
configure_stream_local("TIME_ESTIMATE_TO_TARGET", 1.0f);
configure_stream_local("TRAJECTORY_REPRESENTATION_WAYPOINTS", 5.0f);
configure_stream_local("VFR_HUD", 4.0f);
configure_stream_local("VIBRATION", 0.5f);
configure_stream_local("WIND_COV", 1.0f);
Expand Down
4 changes: 0 additions & 4 deletions src/modules/mavlink/mavlink_messages.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -116,7 +116,6 @@
#include "streams/SYSTEM_TIME.hpp"
#include "streams/TIME_ESTIMATE_TO_TARGET.hpp"
#include "streams/TIMESYNC.hpp"
#include "streams/TRAJECTORY_REPRESENTATION_WAYPOINTS.hpp"
#include "streams/VFR_HUD.hpp"
#include "streams/VIBRATION.hpp"
#include "streams/WIND_COV.hpp"
Expand Down Expand Up @@ -382,9 +381,6 @@ static const StreamListItem streams_list[] = {
#if defined(MANUAL_CONTROL_HPP)
create_stream_list_item<MavlinkStreamManualControl>(),
#endif // MANUAL_CONTROL_HPP
#if defined(TRAJECTORY_REPRESENTATION_WAYPOINTS_HPP)
create_stream_list_item<MavlinkStreamTrajectoryRepresentationWaypoints>(),
#endif // TRAJECTORY_REPRESENTATION_WAYPOINTS_HPP
#if defined(OPTICAL_FLOW_RAD_HPP)
create_stream_list_item<MavlinkStreamOpticalFlowRad>(),
#endif // OPTICAL_FLOW_RAD_HPP
Expand Down
66 changes: 0 additions & 66 deletions src/modules/mavlink/mavlink_receiver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -256,14 +256,6 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg)
handle_message_tunnel(msg);
break;

case MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER:
handle_message_trajectory_representation_bezier(msg);
break;

case MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS:
handle_message_trajectory_representation_waypoints(msg);
break;

case MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS:
handle_message_onboard_computer_status(msg);
break;
Expand Down Expand Up @@ -1988,64 +1980,6 @@ MavlinkReceiver::handle_message_tunnel(mavlink_message_t *msg)

}

void
MavlinkReceiver::handle_message_trajectory_representation_bezier(mavlink_message_t *msg)
{
mavlink_trajectory_representation_bezier_t trajectory;
mavlink_msg_trajectory_representation_bezier_decode(msg, &trajectory);

vehicle_trajectory_bezier_s trajectory_bezier{};

trajectory_bezier.timestamp = _mavlink_timesync.sync_stamp(trajectory.time_usec);

for (int i = 0; i < vehicle_trajectory_bezier_s::NUMBER_POINTS; ++i) {
trajectory_bezier.control_points[i].position[0] = trajectory.pos_x[i];
trajectory_bezier.control_points[i].position[1] = trajectory.pos_y[i];
trajectory_bezier.control_points[i].position[2] = trajectory.pos_z[i];

trajectory_bezier.control_points[i].delta = trajectory.delta[i];
trajectory_bezier.control_points[i].yaw = trajectory.pos_yaw[i];
}

trajectory_bezier.bezier_order = math::min(trajectory.valid_points, vehicle_trajectory_bezier_s::NUMBER_POINTS);
_trajectory_bezier_pub.publish(trajectory_bezier);
}

void
MavlinkReceiver::handle_message_trajectory_representation_waypoints(mavlink_message_t *msg)
{
mavlink_trajectory_representation_waypoints_t trajectory;
mavlink_msg_trajectory_representation_waypoints_decode(msg, &trajectory);

vehicle_trajectory_waypoint_s trajectory_waypoint{};

const int number_valid_points = math::min(trajectory.valid_points, vehicle_trajectory_waypoint_s::NUMBER_POINTS);

for (int i = 0; i < number_valid_points; ++i) {
trajectory_waypoint.waypoints[i].position[0] = trajectory.pos_x[i];
trajectory_waypoint.waypoints[i].position[1] = trajectory.pos_y[i];
trajectory_waypoint.waypoints[i].position[2] = trajectory.pos_z[i];

trajectory_waypoint.waypoints[i].velocity[0] = trajectory.vel_x[i];
trajectory_waypoint.waypoints[i].velocity[1] = trajectory.vel_y[i];
trajectory_waypoint.waypoints[i].velocity[2] = trajectory.vel_z[i];

trajectory_waypoint.waypoints[i].acceleration[0] = trajectory.acc_x[i];
trajectory_waypoint.waypoints[i].acceleration[1] = trajectory.acc_y[i];
trajectory_waypoint.waypoints[i].acceleration[2] = trajectory.acc_z[i];

trajectory_waypoint.waypoints[i].yaw = trajectory.pos_yaw[i];
trajectory_waypoint.waypoints[i].yaw_speed = trajectory.vel_yaw[i];

trajectory_waypoint.waypoints[i].point_valid = true;

trajectory_waypoint.waypoints[i].type = UINT8_MAX;
}

trajectory_waypoint.timestamp = hrt_absolute_time();
_trajectory_waypoint_pub.publish(trajectory_waypoint);
}

void
MavlinkReceiver::handle_message_rc_channels_override(mavlink_message_t *msg)
{
Expand Down
6 changes: 0 additions & 6 deletions src/modules/mavlink/mavlink_receiver.h
Original file line number Diff line number Diff line change
Expand Up @@ -110,8 +110,6 @@
#include <uORB/topics/vehicle_odometry.h>
#include <uORB/topics/vehicle_rates_setpoint.h>
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/vehicle_trajectory_bezier.h>
#include <uORB/topics/vehicle_trajectory_waypoint.h>
#include <uORB/topics/velocity_limits.h>

#if !defined(CONSTRAINED_FLASH)
Expand Down Expand Up @@ -201,8 +199,6 @@ class MavlinkReceiver : public ModuleParams
void handle_message_set_position_target_local_ned(mavlink_message_t *msg);
void handle_message_statustext(mavlink_message_t *msg);
void handle_message_tunnel(mavlink_message_t *msg);
void handle_message_trajectory_representation_bezier(mavlink_message_t *msg);
void handle_message_trajectory_representation_waypoints(mavlink_message_t *msg);
void handle_message_utm_global_position(mavlink_message_t *msg);
#if defined(MAVLINK_MSG_ID_SET_VELOCITY_LIMITS) // For now only defined if development.xml is used
void handle_message_set_velocity_limits(mavlink_message_t *msg);
Expand Down Expand Up @@ -329,8 +325,6 @@ class MavlinkReceiver : public ModuleParams
uORB::Publication<vehicle_odometry_s> _mocap_odometry_pub{ORB_ID(vehicle_mocap_odometry)};
uORB::Publication<vehicle_odometry_s> _visual_odometry_pub{ORB_ID(vehicle_visual_odometry)};
uORB::Publication<vehicle_rates_setpoint_s> _rates_sp_pub{ORB_ID(vehicle_rates_setpoint)};
uORB::Publication<vehicle_trajectory_bezier_s> _trajectory_bezier_pub{ORB_ID(vehicle_trajectory_bezier)};
uORB::Publication<vehicle_trajectory_waypoint_s> _trajectory_waypoint_pub{ORB_ID(vehicle_trajectory_waypoint)};

#if !defined(CONSTRAINED_FLASH)
uORB::Publication<debug_array_s> _debug_array_pub {ORB_ID(debug_array)};
Expand Down
124 changes: 0 additions & 124 deletions src/modules/mavlink/streams/TRAJECTORY_REPRESENTATION_WAYPOINTS.hpp

This file was deleted.

9 changes: 0 additions & 9 deletions src/modules/uxrce_dds_client/dds_topics.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -71,9 +71,6 @@ publications:
- topic: /fmu/out/vehicle_status
type: px4_msgs::msg::VehicleStatus

- topic: /fmu/out/vehicle_trajectory_waypoint_desired
type: px4_msgs::msg::VehicleTrajectoryWaypoint

# Create uORB::Publication
subscriptions:
- topic: /fmu/in/register_ext_component_request
Expand Down Expand Up @@ -142,12 +139,6 @@ subscriptions:
- topic: /fmu/in/vehicle_command_mode_executor
type: px4_msgs::msg::VehicleCommand

- topic: /fmu/in/vehicle_trajectory_bezier
type: px4_msgs::msg::VehicleTrajectoryBezier

- topic: /fmu/in/vehicle_trajectory_waypoint
type: px4_msgs::msg::VehicleTrajectoryWaypoint

- topic: /fmu/in/vehicle_thrust_setpoint
type: px4_msgs::msg::VehicleThrustSetpoint

Expand Down
3 changes: 0 additions & 3 deletions src/modules/zenoh/Kconfig
Original file line number Diff line number Diff line change
Expand Up @@ -46,9 +46,6 @@ if MODULES_ZENOH
select ZENOH_PUBSUB_VEHICLE_ODOMETRY
select ZENOH_PUBSUB_VEHICLE_RATES_SETPOINT
select ZENOH_PUBSUB_VEHICLE_COMMAND
select ZENOH_PUBSUB_VEHICLE_TRAJECTORY_BEZIER
select ZENOH_PUBSUB_VEHICLE_TRAJECTORY_WAYPOINT

config ZENOH_PUBSUB_ALL
bool "All"

Expand Down
Loading

0 comments on commit 4998fe9

Please sign in to comment.