Skip to content

Commit 461557a

Browse files
committed
Merge pull request #754 from julianoes/beta_mavlink2_camera
Beta mavlink2: onboard camera capture
2 parents ca2514b + 3d47ba1 commit 461557a

File tree

3 files changed

+59
-2
lines changed

3 files changed

+59
-2
lines changed

src/modules/mavlink/mavlink_main.cpp

+14-1
Original file line numberDiff line numberDiff line change
@@ -1652,6 +1652,8 @@ Mavlink::task_main(int argc, char *argv[])
16521652
case 'm':
16531653
if (strcmp(optarg, "custom") == 0) {
16541654
_mode = MAVLINK_MODE_CUSTOM;
1655+
} else if (strcmp(optarg, "camera") == 0) {
1656+
_mode = MAVLINK_MODE_CAMERA;
16551657
}
16561658

16571659
break;
@@ -1695,14 +1697,18 @@ Mavlink::task_main(int argc, char *argv[])
16951697
warnx("mode: CUSTOM");
16961698
break;
16971699

1700+
case MAVLINK_MODE_CAMERA:
1701+
warnx("mode: CAMERA");
1702+
break;
1703+
16981704
default:
16991705
warnx("ERROR: Unknown mode");
17001706
break;
17011707
}
17021708

17031709
_mavlink_wpm_comp_id = MAV_COMP_ID_MISSIONPLANNER;
17041710

1705-
warnx("data rate: %d bps, port: %s, baud: %d", _datarate, _device_name, (int)_baudrate);
1711+
warnx("data rate: %d Bytes/s, port: %s, baud: %d", _datarate, _device_name, _baudrate);
17061712

17071713
/* flush stdout in case MAVLink is about to take it over */
17081714
fflush(stdout);
@@ -1765,6 +1771,13 @@ Mavlink::task_main(int argc, char *argv[])
17651771
configure_stream("NAMED_VALUE_FLOAT", 1.0f * rate_mult);
17661772
break;
17671773

1774+
case MAVLINK_MODE_CAMERA:
1775+
configure_stream("SYS_STATUS", 1.0f);
1776+
configure_stream("ATTITUDE", 15.0f * rate_mult);
1777+
configure_stream("GLOBAL_POSITION_INT", 15.0f * rate_mult);
1778+
configure_stream("CAMERA_CAPTURE", 1.0f);
1779+
break;
1780+
17681781
default:
17691782
break;
17701783
}

src/modules/mavlink/mavlink_main.h

+2-1
Original file line numberDiff line numberDiff line change
@@ -146,7 +146,8 @@ class Mavlink
146146

147147
enum MAVLINK_MODE {
148148
MAVLINK_MODE_NORMAL = 0,
149-
MAVLINK_MODE_CUSTOM
149+
MAVLINK_MODE_CUSTOM,
150+
MAVLINK_MODE_CAMERA
150151
};
151152

152153
void set_mode(enum MAVLINK_MODE);

src/modules/mavlink/mavlink_messages.cpp

+43
Original file line numberDiff line numberDiff line change
@@ -1215,6 +1215,48 @@ class MavlinkStreamNamedValueFloat : public MavlinkStream
12151215
}
12161216
};
12171217

1218+
class MavlinkStreamCameraCapture : public MavlinkStream
1219+
{
1220+
public:
1221+
const char *get_name()
1222+
{
1223+
return "CAMERA_CAPTURE";
1224+
}
1225+
1226+
MavlinkStream *new_instance()
1227+
{
1228+
return new MavlinkStreamCameraCapture();
1229+
}
1230+
1231+
private:
1232+
MavlinkOrbSubscription *status_sub;
1233+
struct vehicle_status_s *status;
1234+
1235+
protected:
1236+
void subscribe(Mavlink *mavlink)
1237+
{
1238+
status_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_status));
1239+
status = (struct vehicle_status_s *)status_sub->get_data();
1240+
1241+
1242+
}
1243+
1244+
void send(const hrt_abstime t)
1245+
{
1246+
(void)status_sub->update(t);
1247+
1248+
if (status->arming_state == ARMING_STATE_ARMED
1249+
|| status->arming_state == ARMING_STATE_ARMED_ERROR) {
1250+
1251+
/* send camera capture on */
1252+
mavlink_msg_command_long_send(_channel, 42, 30, MAV_CMD_DO_CONTROL_VIDEO, 0, 0, 0, 0, 1, 0, 0, 0);
1253+
} else {
1254+
/* send camera capture off */
1255+
mavlink_msg_command_long_send(_channel, 42, 30, MAV_CMD_DO_CONTROL_VIDEO, 0, 0, 0, 0, 0, 0, 0, 0);
1256+
}
1257+
}
1258+
};
1259+
12181260
MavlinkStream *streams_list[] = {
12191261
new MavlinkStreamHeartbeat(),
12201262
new MavlinkStreamSysStatus(),
@@ -1240,5 +1282,6 @@ MavlinkStream *streams_list[] = {
12401282
new MavlinkStreamOpticalFlow(),
12411283
new MavlinkStreamAttitudeControls(),
12421284
new MavlinkStreamNamedValueFloat(),
1285+
new MavlinkStreamCameraCapture(),
12431286
nullptr
12441287
};

0 commit comments

Comments
 (0)