mirror of https://github.com/ArduPilot/ardupilot
autotest: more test for emitted digicam command-long messages
This commit is contained in:
parent
187ae07225
commit
0e2261832e
|
@ -5620,9 +5620,9 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
||||||
0,
|
0,
|
||||||
0)
|
0)
|
||||||
|
|
||||||
self.context_collect('COMMAND_LONG')
|
|
||||||
|
|
||||||
self.progress("Sending control message")
|
self.progress("Sending control message")
|
||||||
|
self.context_push()
|
||||||
|
self.context_collect('COMMAND_LONG')
|
||||||
self.mav.mav.digicam_control_send(
|
self.mav.mav.digicam_control_send(
|
||||||
1, # target_system
|
1, # target_system
|
||||||
1, # target_component
|
1, # target_component
|
||||||
|
@ -5641,6 +5641,52 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
||||||
'command': mavutil.mavlink.MAV_CMD_DO_DIGICAM_CONTROL,
|
'command': mavutil.mavlink.MAV_CMD_DO_DIGICAM_CONTROL,
|
||||||
'param6': 17,
|
'param6': 17,
|
||||||
}, timeout=2, check_context=True)
|
}, 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):
|
def SkidSteer(self):
|
||||||
'''Check skid-steering'''
|
'''Check skid-steering'''
|
||||||
|
|
|
@ -438,7 +438,7 @@ void AP_Camera::cam_mode_toggle(uint8_t instance)
|
||||||
}
|
}
|
||||||
|
|
||||||
// configure camera
|
// 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);
|
WITH_SEMAPHORE(_rsem);
|
||||||
|
|
||||||
|
@ -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);
|
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);
|
WITH_SEMAPHORE(_rsem);
|
||||||
|
|
||||||
|
@ -462,7 +462,7 @@ void AP_Camera::configure(uint8_t instance, float shooting_mode, float shutter_s
|
||||||
}
|
}
|
||||||
|
|
||||||
// handle camera control
|
// 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);
|
WITH_SEMAPHORE(_rsem);
|
||||||
|
|
||||||
|
@ -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);
|
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);
|
WITH_SEMAPHORE(_rsem);
|
||||||
|
|
||||||
|
|
|
@ -96,12 +96,12 @@ public:
|
||||||
void send_camera_settings(mavlink_channel_t chan);
|
void send_camera_settings(mavlink_channel_t chan);
|
||||||
|
|
||||||
// configure camera
|
// 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(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, 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, int32_t exposure_type, int32_t cmd_id, float engine_cutoff_time);
|
||||||
|
|
||||||
// handle camera control
|
// 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(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, uint32_t shooting_cmd, uint32_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
|
// set camera trigger distance in a mission
|
||||||
void set_trigger_distance(float distance_m);
|
void set_trigger_distance(float distance_m);
|
||||||
|
|
|
@ -161,7 +161,7 @@ void AP_Camera_Backend::stop_capture()
|
||||||
}
|
}
|
||||||
|
|
||||||
// handle camera control
|
// 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
|
// take picture
|
||||||
if (shooting_cmd == 1) {
|
if (shooting_cmd == 1) {
|
||||||
|
|
|
@ -89,10 +89,10 @@ public:
|
||||||
virtual void handle_message(mavlink_channel_t chan, const mavlink_message_t &msg) {}
|
virtual void handle_message(mavlink_channel_t chan, const mavlink_message_t &msg) {}
|
||||||
|
|
||||||
// configure camera
|
// 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
|
// 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
|
// set camera trigger distance in meters
|
||||||
void set_trigger_distance(float distance_m) { _params.trigg_dist.set(distance_m); }
|
void set_trigger_distance(float distance_m) { _params.trigg_dist.set(distance_m); }
|
||||||
|
|
|
@ -19,7 +19,7 @@ bool AP_Camera_MAVLink::trigger_pic()
|
||||||
}
|
}
|
||||||
|
|
||||||
// configure camera
|
// 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
|
// convert to mavlink message and send to all components
|
||||||
mavlink_command_long_t mav_cmd_long = {};
|
mavlink_command_long_t mav_cmd_long = {};
|
||||||
|
@ -39,7 +39,7 @@ void AP_Camera_MAVLink::configure(float shooting_mode, float shutter_speed, floa
|
||||||
}
|
}
|
||||||
|
|
||||||
// handle camera control message
|
// 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
|
// take picture and ignore other arguments
|
||||||
if (shooting_cmd == 1) {
|
if (shooting_cmd == 1) {
|
||||||
|
|
|
@ -36,10 +36,10 @@ public:
|
||||||
bool trigger_pic() override;
|
bool trigger_pic() override;
|
||||||
|
|
||||||
// configure camera
|
// 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
|
// 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
|
#endif // AP_CAMERA_MAVLINK_ENABLED
|
||||||
|
|
|
@ -44,7 +44,7 @@ bool AP_Camera_Servo::trigger_pic()
|
||||||
}
|
}
|
||||||
|
|
||||||
// configure camera
|
// 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
|
// designed to control Blackmagic Micro Cinema Camera (BMMCC) cameras
|
||||||
// if the message contains non zero values then use them for the below functions
|
// if the message contains non zero values then use them for the below functions
|
||||||
|
|
|
@ -39,7 +39,7 @@ public:
|
||||||
bool trigger_pic() override;
|
bool trigger_pic() override;
|
||||||
|
|
||||||
// configure camera
|
// 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:
|
private:
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue