mavlink: delete fake CAMERA_CAPTURE stream

This commit is contained in:
Daniel Agar
2021-03-11 14:32:08 -05:00
committed by Lorenz Meier
parent d98e1ded6b
commit ee7b6c0e9f
2 changed files with 0 additions and 73 deletions
-1
View File
@@ -1572,7 +1572,6 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
configure_stream_local("ATTITUDE_QUATERNION", 50.0f);
configure_stream_local("ATTITUDE_TARGET", 10.0f);
configure_stream_local("BATTERY_STATUS", 0.5f);
configure_stream_local("CAMERA_CAPTURE", 2.0f);
configure_stream_local("CAMERA_IMAGE_CAPTURED", unlimited_rate);
configure_stream_local("COLLISION", unlimited_rate);
configure_stream_local("ESTIMATOR_STATUS", 1.0f);
-72
View File
@@ -312,77 +312,6 @@ union px4_custom_mode get_px4_custom_mode(uint8_t nav_state)
return custom_mode;
}
class MavlinkStreamCameraCapture : public MavlinkStream
{
public:
const char *get_name() const override
{
return MavlinkStreamCameraCapture::get_name_static();
}
static constexpr const char *get_name_static()
{
return "CAMERA_CAPTURE";
}
static constexpr uint16_t get_id_static()
{
return 0;
}
uint16_t get_id() override
{
return get_id_static();
}
static MavlinkStream *new_instance(Mavlink *mavlink)
{
return new MavlinkStreamCameraCapture(mavlink);
}
unsigned get_size() override
{
return MAVLINK_MSG_ID_COMMAND_LONG_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES;
}
private:
uORB::Subscription _status_sub{ORB_ID(vehicle_status)};
/* do not allow top copying this class */
MavlinkStreamCameraCapture(MavlinkStreamCameraCapture &) = delete;
MavlinkStreamCameraCapture &operator = (const MavlinkStreamCameraCapture &) = delete;
protected:
explicit MavlinkStreamCameraCapture(Mavlink *mavlink) : MavlinkStream(mavlink)
{}
bool send() override
{
vehicle_status_s status;
if (_status_sub.update(&status)) {
mavlink_command_long_t msg{};
msg.target_system = 0;
msg.target_component = MAV_COMP_ID_ALL;
msg.command = MAV_CMD_DO_CONTROL_VIDEO;
msg.confirmation = 0;
msg.param1 = 0;
msg.param2 = 0;
msg.param3 = 0;
/* set camera capture ON/OFF depending on arming state */
msg.param4 = (status.arming_state == vehicle_status_s::ARMING_STATE_ARMED) ? 1 : 0;
msg.param5 = 0;
msg.param6 = 0;
msg.param7 = 0;
mavlink_msg_command_long_send_struct(_mavlink->get_channel(), &msg);
}
return true;
}
};
static const StreamListItem streams_list[] = {
#if defined(HEARTBEAT_HPP)
create_stream_list_item<MavlinkStreamHeartbeat>(),
@@ -527,7 +456,6 @@ static const StreamListItem streams_list[] = {
#if defined(NAV_CONTROLLER_OUTPUT_HPP)
create_stream_list_item<MavlinkStreamNavControllerOutput>(),
#endif // NAV_CONTROLLER_OUTPUT_HPP
create_stream_list_item<MavlinkStreamCameraCapture>(),
#if defined(CAMERA_TRIGGER_HPP)
create_stream_list_item<MavlinkStreamCameraTrigger>(),
#endif // CAMERA_TRIGGER_HPP