AP_Camera.cpp 15 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479
  1. #include "AP_Camera.h"
  2. #include <AP_AHRS/AP_AHRS.h>
  3. #include <AP_Relay/AP_Relay.h>
  4. #include <AP_Math/AP_Math.h>
  5. #include <RC_Channel/RC_Channel.h>
  6. #include <AP_HAL/AP_HAL.h>
  7. #include <GCS_MAVLink/GCS_MAVLink.h>
  8. #include <GCS_MAVLink/GCS.h>
  9. #include <SRV_Channel/SRV_Channel.h>
  10. #include <AP_Logger/AP_Logger.h>
  11. #include <AP_GPS/AP_GPS.h>
  12. // ------------------------------
  13. #define CAM_DEBUG DISABLED
  14. const AP_Param::GroupInfo AP_Camera::var_info[] = {
  15. // @Param: TRIGG_TYPE
  16. // @DisplayName: Camera shutter (trigger) type
  17. // @Description: how to trigger the camera to take a picture
  18. // @Values: 0:Servo,1:Relay
  19. // @User: Standard
  20. AP_GROUPINFO("TRIGG_TYPE", 0, AP_Camera, _trigger_type, AP_CAMERA_TRIGGER_DEFAULT_TRIGGER_TYPE),
  21. // @Param: DURATION
  22. // @DisplayName: Duration that shutter is held open
  23. // @Description: How long the shutter will be held open in 10ths of a second (i.e. enter 10 for 1second, 50 for 5seconds)
  24. // @Units: ds
  25. // @Range: 0 50
  26. // @User: Standard
  27. AP_GROUPINFO("DURATION", 1, AP_Camera, _trigger_duration, AP_CAMERA_TRIGGER_DEFAULT_DURATION),
  28. // @Param: SERVO_ON
  29. // @DisplayName: Servo ON PWM value
  30. // @Description: PWM value in microseconds to move servo to when shutter is activated
  31. // @Units: PWM
  32. // @Range: 1000 2000
  33. // @User: Standard
  34. AP_GROUPINFO("SERVO_ON", 2, AP_Camera, _servo_on_pwm, AP_CAMERA_SERVO_ON_PWM),
  35. // @Param: SERVO_OFF
  36. // @DisplayName: Servo OFF PWM value
  37. // @Description: PWM value in microseconds to move servo to when shutter is deactivated
  38. // @Units: PWM
  39. // @Range: 1000 2000
  40. // @User: Standard
  41. AP_GROUPINFO("SERVO_OFF", 3, AP_Camera, _servo_off_pwm, AP_CAMERA_SERVO_OFF_PWM),
  42. // @Param: TRIGG_DIST
  43. // @DisplayName: Camera trigger distance
  44. // @Description: Distance in meters between camera triggers. If this value is non-zero then the camera will trigger whenever the GPS position changes by this number of meters regardless of what mode the APM is in. Note that this parameter can also be set in an auto mission using the DO_SET_CAM_TRIGG_DIST command, allowing you to enable/disable the triggering of the camera during the flight.
  45. // @User: Standard
  46. // @Units: m
  47. // @Range: 0 1000
  48. AP_GROUPINFO("TRIGG_DIST", 4, AP_Camera, _trigg_dist, 0),
  49. // @Param: RELAY_ON
  50. // @DisplayName: Relay ON value
  51. // @Description: This sets whether the relay goes high or low when it triggers. Note that you should also set RELAY_DEFAULT appropriately for your camera
  52. // @Values: 0:Low,1:High
  53. // @User: Standard
  54. AP_GROUPINFO("RELAY_ON", 5, AP_Camera, _relay_on, 1),
  55. // @Param: MIN_INTERVAL
  56. // @DisplayName: Minimum time between photos
  57. // @Description: Postpone shooting if previous picture was taken less than preset time(ms) ago.
  58. // @User: Standard
  59. // @Units: ms
  60. // @Range: 0 10000
  61. AP_GROUPINFO("MIN_INTERVAL", 6, AP_Camera, _min_interval, 0),
  62. // @Param: MAX_ROLL
  63. // @DisplayName: Maximum photo roll angle.
  64. // @Description: Postpone shooting if roll is greater than limit. (0=Disable, will shoot regardless of roll).
  65. // @User: Standard
  66. // @Units: deg
  67. // @Range: 0 180
  68. AP_GROUPINFO("MAX_ROLL", 7, AP_Camera, _max_roll, 0),
  69. // @Param: FEEDBACK_PIN
  70. // @DisplayName: Camera feedback pin
  71. // @Description: pin number to use for save accurate camera feedback messages. If set to -1 then don't use a pin flag for this, otherwise this is a pin number which if held high after a picture trigger order, will save camera messages when camera really takes a picture. A universal camera hot shoe is needed. The pin should be held high for at least 2 milliseconds for reliable trigger detection. See also the CAM_FEEDBACK_POL option.
  72. // @Values: -1:Disabled,50:AUX1,51:AUX2,52:AUX3,53:AUX4,54:AUX5,55:AUX6
  73. // @User: Standard
  74. // @RebootRequired: True
  75. AP_GROUPINFO("FEEDBACK_PIN", 8, AP_Camera, _feedback_pin, AP_CAMERA_FEEDBACK_DEFAULT_FEEDBACK_PIN),
  76. // @Param: FEEDBACK_POL
  77. // @DisplayName: Camera feedback pin polarity
  78. // @Description: Polarity for feedback pin. If this is 1 then the feedback pin should go high on trigger. If set to 0 then it should go low
  79. // @Values: 0:TriggerLow,1:TriggerHigh
  80. // @User: Standard
  81. AP_GROUPINFO("FEEDBACK_POL", 9, AP_Camera, _feedback_polarity, 1),
  82. // @Param: AUTO_ONLY
  83. // @DisplayName: Distance-trigging in AUTO mode only
  84. // @Description: When enabled, trigging by distance is done in AUTO mode only.
  85. // @Values: 0:Always,1:Only when in AUTO
  86. // @User: Standard
  87. AP_GROUPINFO("AUTO_ONLY", 10, AP_Camera, _auto_mode_only, 0),
  88. // @Param: TYPE
  89. // @DisplayName: Type of camera (0: None, 1: BMMCC)
  90. // @Description: Set the camera type that is being used, certain cameras have custom functions that need further configuration, this enables that.
  91. // @Values: 0:Default,1:BMMCC
  92. // @User: Standard
  93. AP_GROUPINFO("TYPE", 11, AP_Camera, _type, 0),
  94. AP_GROUPEND
  95. };
  96. extern const AP_HAL::HAL& hal;
  97. /// Servo operated camera
  98. void
  99. AP_Camera::servo_pic()
  100. {
  101. SRV_Channels::set_output_pwm(SRV_Channel::k_cam_trigger, _servo_on_pwm);
  102. // leave a message that it should be active for this many loops (assumes 50hz loops)
  103. _trigger_counter = constrain_int16(_trigger_duration*5,0,255);
  104. }
  105. /// basic relay activation
  106. void
  107. AP_Camera::relay_pic()
  108. {
  109. AP_Relay *_apm_relay = AP::relay();
  110. if (_apm_relay == nullptr) {
  111. return;
  112. }
  113. if (_relay_on) {
  114. _apm_relay->on(0);
  115. } else {
  116. _apm_relay->off(0);
  117. }
  118. // leave a message that it should be active for this many loops (assumes 50hz loops)
  119. _trigger_counter = constrain_int16(_trigger_duration*5,0,255);
  120. }
  121. /// single entry point to take pictures
  122. /// set send_mavlink_msg to true to send DO_DIGICAM_CONTROL message to all components
  123. void AP_Camera::trigger_pic()
  124. {
  125. setup_feedback_callback();
  126. _image_index++;
  127. switch (_trigger_type) {
  128. case AP_CAMERA_TRIGGER_TYPE_SERVO:
  129. servo_pic(); // Servo operated camera
  130. break;
  131. case AP_CAMERA_TRIGGER_TYPE_RELAY:
  132. relay_pic(); // basic relay activation
  133. break;
  134. }
  135. log_picture();
  136. }
  137. /// de-activate the trigger after some delay, but without using a delay() function
  138. /// should be called at 50hz
  139. void
  140. AP_Camera::trigger_pic_cleanup()
  141. {
  142. if (_trigger_counter) {
  143. _trigger_counter--;
  144. } else {
  145. switch (_trigger_type) {
  146. case AP_CAMERA_TRIGGER_TYPE_SERVO:
  147. SRV_Channels::set_output_pwm(SRV_Channel::k_cam_trigger, _servo_off_pwm);
  148. break;
  149. case AP_CAMERA_TRIGGER_TYPE_RELAY: {
  150. AP_Relay *_apm_relay = AP::relay();
  151. if (_apm_relay == nullptr) {
  152. break;
  153. }
  154. if (_relay_on) {
  155. _apm_relay->off(0);
  156. } else {
  157. _apm_relay->on(0);
  158. }
  159. break;
  160. }
  161. }
  162. }
  163. if (_trigger_counter_cam_function) {
  164. _trigger_counter_cam_function--;
  165. } else {
  166. switch (_type) {
  167. case AP_Camera::CAMERA_TYPE_BMMCC:
  168. SRV_Channels::set_output_pwm(SRV_Channel::k_cam_iso, _servo_off_pwm);
  169. break;
  170. }
  171. }
  172. }
  173. /// decode deprecated MavLink message that controls camera.
  174. void
  175. AP_Camera::control_msg(const mavlink_message_t &msg)
  176. {
  177. __mavlink_digicam_control_t packet;
  178. mavlink_msg_digicam_control_decode(&msg, &packet);
  179. control(packet.session, packet.zoom_pos, packet.zoom_step, packet.focus_lock, packet.shot, packet.command_id);
  180. }
  181. void AP_Camera::configure(float shooting_mode, float shutter_speed, float aperture, float ISO, float exposure_type, float cmd_id, float engine_cutoff_time)
  182. {
  183. // we cannot process the configure command so convert to mavlink message
  184. // and send to all components in case they and process it
  185. mavlink_message_t msg;
  186. mavlink_command_long_t mav_cmd_long = {};
  187. // convert mission command to mavlink command_long
  188. mav_cmd_long.command = MAV_CMD_DO_DIGICAM_CONFIGURE;
  189. mav_cmd_long.param1 = shooting_mode;
  190. mav_cmd_long.param2 = shutter_speed;
  191. mav_cmd_long.param3 = aperture;
  192. mav_cmd_long.param4 = ISO;
  193. mav_cmd_long.param5 = exposure_type;
  194. mav_cmd_long.param6 = cmd_id;
  195. mav_cmd_long.param7 = engine_cutoff_time;
  196. // Encode Command long into MAVLINK msg
  197. mavlink_msg_command_long_encode(0, 0, &msg, &mav_cmd_long);
  198. // send to all components
  199. GCS_MAVLINK::send_to_components(msg);
  200. if (_type == AP_Camera::CAMERA_TYPE_BMMCC) {
  201. // Set a trigger for the additional functions that are flip controlled (so far just ISO and Record Start / Stop use this method, will add others if required)
  202. _trigger_counter_cam_function = constrain_int16(_trigger_duration*5,0,255);
  203. // If the message contains non zero values then use them for the below functions
  204. if (ISO > 0) {
  205. SRV_Channels::set_output_pwm(SRV_Channel::k_cam_iso, _servo_on_pwm);
  206. }
  207. if (aperture > 0) {
  208. SRV_Channels::set_output_pwm(SRV_Channel::k_cam_aperture, (int)aperture);
  209. }
  210. if (shutter_speed > 0) {
  211. SRV_Channels::set_output_pwm(SRV_Channel::k_cam_shutter_speed, (int)shutter_speed);
  212. }
  213. // Use the shooting mode PWM value for the BMMCC as the focus control - no need to modify or create a new MAVlink message type.
  214. if (shooting_mode > 0) {
  215. SRV_Channels::set_output_pwm(SRV_Channel::k_cam_focus, (int)shooting_mode);
  216. }
  217. }
  218. }
  219. void AP_Camera::control(float session, float zoom_pos, float zoom_step, float focus_lock, float shooting_cmd, float cmd_id)
  220. {
  221. // take picture
  222. if (is_equal(shooting_cmd,1.0f)) {
  223. trigger_pic();
  224. }
  225. mavlink_message_t msg;
  226. mavlink_command_long_t mav_cmd_long = {};
  227. // convert command to mavlink command long
  228. mav_cmd_long.command = MAV_CMD_DO_DIGICAM_CONTROL;
  229. mav_cmd_long.param1 = session;
  230. mav_cmd_long.param2 = zoom_pos;
  231. mav_cmd_long.param3 = zoom_step;
  232. mav_cmd_long.param4 = focus_lock;
  233. mav_cmd_long.param5 = shooting_cmd;
  234. mav_cmd_long.param6 = cmd_id;
  235. // Encode Command long into MAVLINK msg
  236. mavlink_msg_command_long_encode(0, 0, &msg, &mav_cmd_long);
  237. // send to all components
  238. GCS_MAVLINK::send_to_components(msg);
  239. }
  240. /*
  241. Send camera feedback to the GCS
  242. */
  243. void AP_Camera::send_feedback(mavlink_channel_t chan)
  244. {
  245. const AP_AHRS &ahrs = AP::ahrs();
  246. float altitude, altitude_rel;
  247. if (current_loc.relative_alt) {
  248. altitude = current_loc.alt+ahrs.get_home().alt;
  249. altitude_rel = current_loc.alt;
  250. } else {
  251. altitude = current_loc.alt;
  252. altitude_rel = current_loc.alt - ahrs.get_home().alt;
  253. }
  254. mavlink_msg_camera_feedback_send(
  255. chan,
  256. AP::gps().time_epoch_usec(),
  257. 0, 0, _image_index,
  258. current_loc.lat, current_loc.lng,
  259. altitude*1e-2f, altitude_rel*1e-2f,
  260. ahrs.roll_sensor*1e-2f, ahrs.pitch_sensor*1e-2f, ahrs.yaw_sensor*1e-2f,
  261. 0.0f, CAMERA_FEEDBACK_PHOTO, _camera_trigger_logged);
  262. }
  263. /* update; triggers by distance moved
  264. */
  265. void AP_Camera::update()
  266. {
  267. if (AP::gps().status() < AP_GPS::GPS_OK_FIX_3D) {
  268. return;
  269. }
  270. if (is_zero(_trigg_dist)) {
  271. return;
  272. }
  273. if (_last_location.lat == 0 && _last_location.lng == 0) {
  274. _last_location = current_loc;
  275. return;
  276. }
  277. if (_last_location.lat == current_loc.lat && _last_location.lng == current_loc.lng) {
  278. // we haven't moved - this can happen as update() may
  279. // be called without a new GPS fix
  280. return;
  281. }
  282. if (current_loc.get_distance(_last_location) < _trigg_dist) {
  283. return;
  284. }
  285. if (_max_roll > 0 && fabsf(AP::ahrs().roll_sensor*1e-2f) > _max_roll) {
  286. return;
  287. }
  288. if (_is_in_auto_mode != true && _auto_mode_only != 0) {
  289. return;
  290. }
  291. uint32_t tnow = AP_HAL::millis();
  292. if (tnow - _last_photo_time < (unsigned) _min_interval) {
  293. return;
  294. }
  295. take_picture();
  296. _last_location = current_loc;
  297. _last_photo_time = tnow;
  298. }
  299. /*
  300. interrupt handler for interrupt based feedback trigger
  301. */
  302. void AP_Camera::feedback_pin_isr(uint8_t pin, bool high, uint32_t timestamp_us)
  303. {
  304. _feedback_timestamp_us = timestamp_us;
  305. _camera_trigger_count++;
  306. }
  307. /*
  308. check if feedback pin is high for timer based feedback trigger, when
  309. attach_interrupt fails
  310. */
  311. void AP_Camera::feedback_pin_timer(void)
  312. {
  313. uint8_t pin_state = hal.gpio->read(_feedback_pin);
  314. uint8_t trigger_polarity = _feedback_polarity==0?0:1;
  315. if (pin_state == trigger_polarity &&
  316. _last_pin_state != trigger_polarity) {
  317. _feedback_timestamp_us = AP_HAL::micros();
  318. _camera_trigger_count++;
  319. }
  320. _last_pin_state = pin_state;
  321. }
  322. /*
  323. setup a callback for a feedback pin. When on PX4 with the right FMU
  324. mode we can use the microsecond timer.
  325. */
  326. void AP_Camera::setup_feedback_callback(void)
  327. {
  328. if (_feedback_pin <= 0 || _timer_installed || _isr_installed) {
  329. // invalid or already installed
  330. return;
  331. }
  332. // ensure we are in input mode
  333. hal.gpio->pinMode(_feedback_pin, HAL_GPIO_INPUT);
  334. // enable pullup/pulldown
  335. uint8_t trigger_polarity = _feedback_polarity==0?0:1;
  336. hal.gpio->write(_feedback_pin, !trigger_polarity);
  337. if (hal.gpio->attach_interrupt(_feedback_pin, FUNCTOR_BIND_MEMBER(&AP_Camera::feedback_pin_isr, void, uint8_t, bool, uint32_t),
  338. trigger_polarity?AP_HAL::GPIO::INTERRUPT_RISING:AP_HAL::GPIO::INTERRUPT_FALLING)) {
  339. _isr_installed = true;
  340. } else {
  341. // install a 1kHz timer to check feedback pin
  342. hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&AP_Camera::feedback_pin_timer, void));
  343. _timer_installed = true;
  344. }
  345. }
  346. // log_picture - log picture taken and send feedback to GCS
  347. void AP_Camera::log_picture()
  348. {
  349. AP_Logger *logger = AP_Logger::get_singleton();
  350. if (logger == nullptr) {
  351. return;
  352. }
  353. if (!using_feedback_pin()) {
  354. gcs().send_message(MSG_CAMERA_FEEDBACK);
  355. if (logger->should_log(log_camera_bit)) {
  356. logger->Write_Camera(current_loc);
  357. }
  358. } else {
  359. if (logger->should_log(log_camera_bit)) {
  360. logger->Write_Trigger(current_loc);
  361. }
  362. }
  363. }
  364. // take_picture - take a picture
  365. void AP_Camera::take_picture()
  366. {
  367. // take a local picture:
  368. trigger_pic();
  369. // tell all of our components to take a picture:
  370. mavlink_command_long_t cmd_msg;
  371. memset(&cmd_msg, 0, sizeof(cmd_msg));
  372. cmd_msg.command = MAV_CMD_DO_DIGICAM_CONTROL;
  373. cmd_msg.param5 = 1;
  374. // create message
  375. mavlink_message_t msg;
  376. mavlink_msg_command_long_encode(0, 0, &msg, &cmd_msg);
  377. // forward to all components
  378. GCS_MAVLINK::send_to_components(msg);
  379. }
  380. /*
  381. update camera trigger - 50Hz
  382. */
  383. void AP_Camera::update_trigger()
  384. {
  385. trigger_pic_cleanup();
  386. if (_camera_trigger_logged != _camera_trigger_count) {
  387. uint32_t timestamp32 = _feedback_timestamp_us;
  388. _camera_trigger_logged = _camera_trigger_count;
  389. gcs().send_message(MSG_CAMERA_FEEDBACK);
  390. AP_Logger *logger = AP_Logger::get_singleton();
  391. if (logger != nullptr) {
  392. if (logger->should_log(log_camera_bit)) {
  393. uint32_t tdiff = AP_HAL::micros() - timestamp32;
  394. uint64_t timestamp = AP_HAL::micros64();
  395. logger->Write_Camera(current_loc, timestamp - tdiff);
  396. }
  397. }
  398. }
  399. }
  400. // singleton instance
  401. AP_Camera *AP_Camera::_singleton;
  402. namespace AP {
  403. AP_Camera *camera()
  404. {
  405. return AP_Camera::get_singleton();
  406. }
  407. }