AP_Camera: changed "int" to "int16_t" and "long" to "int32_t" here and there.

This commit is contained in:
rmackay9 2012-07-15 16:26:12 +09:00
parent c73f7ef3ab
commit 5616b1769b
2 changed files with 5 additions and 5 deletions

View File

@ -5,7 +5,7 @@
#include <../RC_Channel/RC_Channel_aux.h>
extern RC_Channel_aux* g_rc_function[RC_Channel_aux::k_nr_aux_servo_functions]; // the aux. servo ch. assigned to each function
extern long wp_distance;
extern int32_t wp_distance;
extern AP_Relay relay;
// ------------------------------

View File

@ -36,15 +36,15 @@ public:
void configure_msg(mavlink_message_t* msg);
void control_msg(mavlink_message_t* msg);
int picture_time; ///< waypoint trigger variable
long wp_distance_min; ///< take picture if distance to WP is smaller than this
int16_t picture_time; ///< waypoint trigger variable
int32_t wp_distance_min; ///< take picture if distance to WP is smaller than this
static const struct AP_Param::GroupInfo var_info[];
private:
uint8_t keep_cam_trigg_active_cycles; ///< event loop cycles to keep trigger active
int thr_pic; ///< timer variable for throttle_pic
int camtrig; ///< PK6 chosen as it not near anything so safer for soldering
int16_t thr_pic; ///< timer variable for throttle_pic
int16_t camtrig; ///< PK6 chosen as it not near anything so safer for soldering
AP_Int8 trigger_type; ///< 0=Servo, 1=relay, 2=throttle_off time, 3=throttle_off waypoint, 4=transistor