Skip to content

Commit

Permalink
autotest: more test for emitted digicam command-long messages
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker committed Nov 2, 2023
1 parent 187ae07 commit 0e22618
Show file tree
Hide file tree
Showing 9 changed files with 65 additions and 19 deletions.
50 changes: 48 additions & 2 deletions Tools/autotest/rover.py
Original file line number Diff line number Diff line change
Expand Up @@ -5620,9 +5620,9 @@ def SendToComponents(self):
0,
0)

self.context_collect('COMMAND_LONG')

self.progress("Sending control message")
self.context_push()
self.context_collect('COMMAND_LONG')
self.mav.mav.digicam_control_send(
1, # target_system
1, # target_component
Expand All @@ -5641,6 +5641,52 @@ def SendToComponents(self):
'command': mavutil.mavlink.MAV_CMD_DO_DIGICAM_CONTROL,
'param6': 17,
}, timeout=2, check_context=True)
self.context_pop()

# test sending via commands:
for run_cmd in self.run_cmd, self.run_cmd_int:
self.progress("Sending control command")
self.context_push()
self.context_collect('COMMAND_LONG')
run_cmd(mavutil.mavlink.MAV_CMD_DO_DIGICAM_CONTROL,
p1=1, # start or keep it up
p2=1, # zoom_pos
p3=0, # zoom_step
p4=0, # focus_lock
p5=0, # 1 shot or start filming
p6=37, # command id (de-dupe field)
)

self.assert_received_message_field_values('COMMAND_LONG', {
'command': mavutil.mavlink.MAV_CMD_DO_DIGICAM_CONTROL,
'param6': 37,
}, timeout=2, check_context=True)

self.context_pop()

# test sending via commands:
for run_cmd in self.run_cmd, self.run_cmd_int:
self.progress("Sending configure command")
self.context_push()
self.context_collect('COMMAND_LONG')
run_cmd(mavutil.mavlink.MAV_CMD_DO_DIGICAM_CONFIGURE,
p1=1,
p2=1,
p3=0,
p4=0,
p5=12,
p6=37
)

self.assert_received_message_field_values('COMMAND_LONG', {
'command': mavutil.mavlink.MAV_CMD_DO_DIGICAM_CONFIGURE,
'param5': 12,
'param6': 37,
}, timeout=2, check_context=True)

self.context_pop()

self.mav.mav.srcSystem = old_srcSystem

def SkidSteer(self):
'''Check skid-steering'''
Expand Down
8 changes: 4 additions & 4 deletions libraries/AP_Camera/AP_Camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -438,7 +438,7 @@ void AP_Camera::cam_mode_toggle(uint8_t instance)
}

// configure camera
void AP_Camera::configure(float shooting_mode, float shutter_speed, float aperture, float ISO, uint32_t exposure_type, uint32_t cmd_id, float engine_cutoff_time)
void AP_Camera::configure(float shooting_mode, float shutter_speed, float aperture, float ISO, int32_t exposure_type, int32_t cmd_id, float engine_cutoff_time)
{
WITH_SEMAPHORE(_rsem);

Expand All @@ -448,7 +448,7 @@ void AP_Camera::configure(float shooting_mode, float shutter_speed, float apertu
primary->configure(shooting_mode, shutter_speed, aperture, ISO, exposure_type, cmd_id, engine_cutoff_time);
}

void AP_Camera::configure(uint8_t instance, float shooting_mode, float shutter_speed, float aperture, float ISO, uint32_t exposure_type, uint32_t cmd_id, float engine_cutoff_time)
void AP_Camera::configure(uint8_t instance, float shooting_mode, float shutter_speed, float aperture, float ISO, int32_t exposure_type, int32_t cmd_id, float engine_cutoff_time)
{
WITH_SEMAPHORE(_rsem);

Expand All @@ -462,7 +462,7 @@ void AP_Camera::configure(uint8_t instance, float shooting_mode, float shutter_s
}

// handle camera control
void AP_Camera::control(float session, float zoom_pos, float zoom_step, float focus_lock, uint32_t shooting_cmd, uint32_t cmd_id)
void AP_Camera::control(float session, float zoom_pos, float zoom_step, float focus_lock, int32_t shooting_cmd, int32_t cmd_id)
{
WITH_SEMAPHORE(_rsem);

Expand All @@ -472,7 +472,7 @@ void AP_Camera::control(float session, float zoom_pos, float zoom_step, float fo
primary->control(session, zoom_pos, zoom_step, focus_lock, shooting_cmd, cmd_id);
}

void AP_Camera::control(uint8_t instance, float session, float zoom_pos, float zoom_step, float focus_lock, uint32_t shooting_cmd, uint32_t cmd_id)
void AP_Camera::control(uint8_t instance, float session, float zoom_pos, float zoom_step, float focus_lock, int32_t shooting_cmd, int32_t cmd_id)
{
WITH_SEMAPHORE(_rsem);

Expand Down
8 changes: 4 additions & 4 deletions libraries/AP_Camera/AP_Camera.h
Original file line number Diff line number Diff line change
Expand Up @@ -96,12 +96,12 @@ class AP_Camera {
void send_camera_settings(mavlink_channel_t chan);

// configure camera
void configure(float shooting_mode, float shutter_speed, float aperture, float ISO, uint32_t exposure_type, uint32_t cmd_id, float engine_cutoff_time);
void configure(uint8_t instance, float shooting_mode, float shutter_speed, float aperture, float ISO, uint32_t exposure_type, uint32_t cmd_id, float engine_cutoff_time);
void configure(float shooting_mode, float shutter_speed, float aperture, float ISO, int32_t exposure_type, int32_t cmd_id, float engine_cutoff_time);
void configure(uint8_t instance, float shooting_mode, float shutter_speed, float aperture, float ISO, int32_t exposure_type, int32_t cmd_id, float engine_cutoff_time);

// handle camera control
void control(float session, float zoom_pos, float zoom_step, float focus_lock, uint32_t shooting_cmd, uint32_t cmd_id);
void control(uint8_t instance, float session, float zoom_pos, float zoom_step, float focus_lock, uint32_t shooting_cmd, uint32_t cmd_id);
void control(float session, float zoom_pos, float zoom_step, float focus_lock, int32_t shooting_cmd, int32_t cmd_id);
void control(uint8_t instance, float session, float zoom_pos, float zoom_step, float focus_lock, int32_t shooting_cmd, int32_t cmd_id);

// set camera trigger distance in a mission
void set_trigger_distance(float distance_m);
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Camera/AP_Camera_Backend.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -161,7 +161,7 @@ void AP_Camera_Backend::stop_capture()
}

// handle camera control
void AP_Camera_Backend::control(float session, float zoom_pos, float zoom_step, float focus_lock, uint32_t shooting_cmd, uint32_t cmd_id)
void AP_Camera_Backend::control(float session, float zoom_pos, float zoom_step, float focus_lock, int32_t shooting_cmd, int32_t cmd_id)
{
// take picture
if (shooting_cmd == 1) {
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_Camera/AP_Camera_Backend.h
Original file line number Diff line number Diff line change
Expand Up @@ -89,10 +89,10 @@ class AP_Camera_Backend
virtual void handle_message(mavlink_channel_t chan, const mavlink_message_t &msg) {}

// configure camera
virtual void configure(float shooting_mode, float shutter_speed, float aperture, float ISO, uint32_t exposure_type, uint32_t cmd_id, float engine_cutoff_time) {}
virtual void configure(float shooting_mode, float shutter_speed, float aperture, float ISO, int32_t exposure_type, int32_t cmd_id, float engine_cutoff_time) {}

// handle camera control
virtual void control(float session, float zoom_pos, float zoom_step, float focus_lock, uint32_t shooting_cmd, uint32_t cmd_id);
virtual void control(float session, float zoom_pos, float zoom_step, float focus_lock, int32_t shooting_cmd, int32_t cmd_id);

// set camera trigger distance in meters
void set_trigger_distance(float distance_m) { _params.trigg_dist.set(distance_m); }
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_Camera/AP_Camera_MAVLink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ bool AP_Camera_MAVLink::trigger_pic()
}

// configure camera
void AP_Camera_MAVLink::configure(float shooting_mode, float shutter_speed, float aperture, float ISO, uint32_t exposure_type, uint32_t cmd_id, float engine_cutoff_time)
void AP_Camera_MAVLink::configure(float shooting_mode, float shutter_speed, float aperture, float ISO, int32_t exposure_type, int32_t cmd_id, float engine_cutoff_time)
{
// convert to mavlink message and send to all components
mavlink_command_long_t mav_cmd_long = {};
Expand All @@ -39,7 +39,7 @@ void AP_Camera_MAVLink::configure(float shooting_mode, float shutter_speed, floa
}

// handle camera control message
void AP_Camera_MAVLink::control(float session, float zoom_pos, float zoom_step, float focus_lock, uint32_t shooting_cmd, uint32_t cmd_id)
void AP_Camera_MAVLink::control(float session, float zoom_pos, float zoom_step, float focus_lock, int32_t shooting_cmd, int32_t cmd_id)
{
// take picture and ignore other arguments
if (shooting_cmd == 1) {
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_Camera/AP_Camera_MAVLink.h
Original file line number Diff line number Diff line change
Expand Up @@ -36,10 +36,10 @@ class AP_Camera_MAVLink : public AP_Camera_Backend
bool trigger_pic() override;

// configure camera
void configure(float shooting_mode, float shutter_speed, float aperture, float ISO, uint32_t exposure_type, uint32_t cmd_id, float engine_cutoff_time) override;
void configure(float shooting_mode, float shutter_speed, float aperture, float ISO, int32_t exposure_type, int32_t cmd_id, float engine_cutoff_time) override;

// handle camera control message
void control(float session, float zoom_pos, float zoom_step, float focus_lock, uint32_t shooting_cmd, uint32_t cmd_id) override;
void control(float session, float zoom_pos, float zoom_step, float focus_lock, int32_t shooting_cmd, int32_t cmd_id) override;
};

#endif // AP_CAMERA_MAVLINK_ENABLED
2 changes: 1 addition & 1 deletion libraries/AP_Camera/AP_Camera_Servo.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ bool AP_Camera_Servo::trigger_pic()
}

// configure camera
void AP_Camera_Servo::configure(float shooting_mode, float shutter_speed, float aperture, float ISO, uint32_t exposure_type, uint32_t cmd_id, float engine_cutoff_time)
void AP_Camera_Servo::configure(float shooting_mode, float shutter_speed, float aperture, float ISO, int32_t exposure_type, int32_t cmd_id, float engine_cutoff_time)
{
// designed to control Blackmagic Micro Cinema Camera (BMMCC) cameras
// if the message contains non zero values then use them for the below functions
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Camera/AP_Camera_Servo.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ class AP_Camera_Servo : public AP_Camera_Backend
bool trigger_pic() override;

// configure camera
void configure(float shooting_mode, float shutter_speed, float aperture, float ISO, uint32_t exposure_type, uint32_t cmd_id, float engine_cutoff_time) override;
void configure(float shooting_mode, float shutter_speed, float aperture, float ISO, int32_t exposure_type, int32_t cmd_id, float engine_cutoff_time) override;

private:

Expand Down

0 comments on commit 0e22618

Please sign in to comment.