forked from Archive/PX4-Autopilot
Merge pull request #1123 from DonLakeFlyer/Warnings
Compiler warning fixes
This commit is contained in:
commit
be7c2ccdeb
|
@ -293,7 +293,7 @@ BlinkM::BlinkM(int bus, int blinkm) :
|
|||
safety_sub_fd(-1),
|
||||
num_of_cells(0),
|
||||
detected_cells_runcount(0),
|
||||
t_led_color({0}),
|
||||
t_led_color{0},
|
||||
t_led_blink(0),
|
||||
led_thread_runcount(0),
|
||||
led_interval(1000),
|
||||
|
|
|
@ -294,23 +294,21 @@ __EXPORT int get_distance_to_arc(struct crosstrack_error_s *crosstrack_error, do
|
|||
// calculate the position of the start and end points. We should not be doing this often
|
||||
// as this function generally will not be called repeatedly when we are out of the sector.
|
||||
|
||||
// TO DO - this is messed up and won't compile
|
||||
float start_disp_x = radius * sinf(arc_start_bearing);
|
||||
float start_disp_y = radius * cosf(arc_start_bearing);
|
||||
float end_disp_x = radius * sinf(_wrapPI(arc_start_bearing + arc_sweep));
|
||||
float end_disp_y = radius * cosf(_wrapPI(arc_start_bearing + arc_sweep));
|
||||
float lon_start = lon_now + start_disp_x / 111111.0f;
|
||||
float lat_start = lat_now + start_disp_y * cosf(lat_now) / 111111.0f;
|
||||
float lon_end = lon_now + end_disp_x / 111111.0f;
|
||||
float lat_end = lat_now + end_disp_y * cosf(lat_now) / 111111.0f;
|
||||
float dist_to_start = get_distance_to_next_waypoint(lat_now, lon_now, lat_start, lon_start);
|
||||
float dist_to_end = get_distance_to_next_waypoint(lat_now, lon_now, lat_end, lon_end);
|
||||
double start_disp_x = (double)radius * sin(arc_start_bearing);
|
||||
double start_disp_y = (double)radius * cos(arc_start_bearing);
|
||||
double end_disp_x = (double)radius * sin(_wrapPI((double)(arc_start_bearing + arc_sweep)));
|
||||
double end_disp_y = (double)radius * cos(_wrapPI((double)(arc_start_bearing + arc_sweep)));
|
||||
double lon_start = lon_now + start_disp_x / 111111.0;
|
||||
double lat_start = lat_now + start_disp_y * cos(lat_now) / 111111.0;
|
||||
double lon_end = lon_now + end_disp_x / 111111.0;
|
||||
double lat_end = lat_now + end_disp_y * cos(lat_now) / 111111.0;
|
||||
double dist_to_start = get_distance_to_next_waypoint(lat_now, lon_now, lat_start, lon_start);
|
||||
double dist_to_end = get_distance_to_next_waypoint(lat_now, lon_now, lat_end, lon_end);
|
||||
|
||||
|
||||
if (dist_to_start < dist_to_end) {
|
||||
crosstrack_error->distance = dist_to_start;
|
||||
crosstrack_error->bearing = get_bearing_to_next_waypoint(lat_now, lon_now, lat_start, lon_start);
|
||||
|
||||
} else {
|
||||
crosstrack_error->past_end = true;
|
||||
crosstrack_error->distance = dist_to_end;
|
||||
|
@ -319,7 +317,7 @@ __EXPORT int get_distance_to_arc(struct crosstrack_error_s *crosstrack_error, do
|
|||
|
||||
}
|
||||
|
||||
crosstrack_error->bearing = _wrapPI(crosstrack_error->bearing);
|
||||
crosstrack_error->bearing = _wrapPI((double)crosstrack_error->bearing);
|
||||
return_value = OK;
|
||||
return return_value;
|
||||
}
|
||||
|
|
|
@ -472,7 +472,7 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
|
|||
// Follow exactly what the mavlink spec says for values: 0.0f for disarm, 1.0f for arm.
|
||||
// We use an float epsilon delta to test float equality.
|
||||
if (cmd->param1 != 0.0f && (fabsf(cmd->param1 - 1.0f) > 2.0f * FLT_EPSILON)) {
|
||||
mavlink_log_info(mavlink_fd, "Unsupported ARM_DISARM parameter: %.6f", cmd->param1);
|
||||
mavlink_log_info(mavlink_fd, "Unsupported ARM_DISARM parameter: %.6f", (double)cmd->param1);
|
||||
|
||||
} else {
|
||||
|
||||
|
@ -634,7 +634,7 @@ int commander_thread_main(int argc, char *argv[])
|
|||
/* welcome user */
|
||||
warnx("starting");
|
||||
|
||||
char *main_states_str[MAIN_STATE_MAX];
|
||||
const char *main_states_str[MAIN_STATE_MAX];
|
||||
main_states_str[MAIN_STATE_MANUAL] = "MANUAL";
|
||||
main_states_str[MAIN_STATE_ALTCTL] = "ALTCTL";
|
||||
main_states_str[MAIN_STATE_POSCTL] = "POSCTL";
|
||||
|
@ -643,7 +643,7 @@ int commander_thread_main(int argc, char *argv[])
|
|||
main_states_str[MAIN_STATE_AUTO_RTL] = "AUTO_RTL";
|
||||
main_states_str[MAIN_STATE_ACRO] = "ACRO";
|
||||
|
||||
char *arming_states_str[ARMING_STATE_MAX];
|
||||
const char *arming_states_str[ARMING_STATE_MAX];
|
||||
arming_states_str[ARMING_STATE_INIT] = "INIT";
|
||||
arming_states_str[ARMING_STATE_STANDBY] = "STANDBY";
|
||||
arming_states_str[ARMING_STATE_ARMED] = "ARMED";
|
||||
|
@ -652,7 +652,7 @@ int commander_thread_main(int argc, char *argv[])
|
|||
arming_states_str[ARMING_STATE_REBOOT] = "REBOOT";
|
||||
arming_states_str[ARMING_STATE_IN_AIR_RESTORE] = "IN_AIR_RESTORE";
|
||||
|
||||
char *nav_states_str[NAVIGATION_STATE_MAX];
|
||||
const char *nav_states_str[NAVIGATION_STATE_MAX];
|
||||
nav_states_str[NAVIGATION_STATE_MANUAL] = "MANUAL";
|
||||
nav_states_str[NAVIGATION_STATE_ALTCTL] = "ALTCTL";
|
||||
nav_states_str[NAVIGATION_STATE_POSCTL] = "POSCTL";
|
||||
|
|
|
@ -414,6 +414,17 @@ FixedwingPositionControl::FixedwingPositionControl() :
|
|||
_attitude_sp_pub(-1),
|
||||
_nav_capabilities_pub(-1),
|
||||
|
||||
_att(),
|
||||
_att_sp(),
|
||||
_nav_capabilities(),
|
||||
_manual(),
|
||||
_airspeed(),
|
||||
_control_mode(),
|
||||
_global_pos(),
|
||||
_pos_sp_triplet(),
|
||||
_sensor_combined(),
|
||||
_range_finder(),
|
||||
|
||||
/* performance counters */
|
||||
_loop_perf(perf_alloc(PC_ELAPSED, "fw l1 control")),
|
||||
|
||||
|
@ -433,18 +444,8 @@ FixedwingPositionControl::FixedwingPositionControl() :
|
|||
_airspeed_valid(false),
|
||||
_groundspeed_undershoot(0.0f),
|
||||
_global_pos_valid(false),
|
||||
_att(),
|
||||
_att_sp(),
|
||||
_nav_capabilities(),
|
||||
_manual(),
|
||||
_airspeed(),
|
||||
_control_mode(),
|
||||
_global_pos(),
|
||||
_pos_sp_triplet(),
|
||||
_sensor_combined(),
|
||||
_mTecs(),
|
||||
_was_pos_control_mode(false),
|
||||
_range_finder()
|
||||
_was_pos_control_mode(false)
|
||||
{
|
||||
_nav_capabilities.turn_distance = 0.0f;
|
||||
|
||||
|
|
|
@ -56,9 +56,9 @@ class BlockOutputLimiter: public SuperBlock
|
|||
{
|
||||
public:
|
||||
// methods
|
||||
BlockOutputLimiter(SuperBlock *parent, const char *name, bool isAngularLimit = false) :
|
||||
BlockOutputLimiter(SuperBlock *parent, const char *name, bool fAngularLimit = false) :
|
||||
SuperBlock(parent, name),
|
||||
_isAngularLimit(isAngularLimit),
|
||||
_isAngularLimit(fAngularLimit),
|
||||
_min(this, "MIN"),
|
||||
_max(this, "MAX")
|
||||
{};
|
||||
|
|
|
@ -67,7 +67,7 @@ __EXPORT void sched_note_switch(FAR struct tcb_s *pFromTcb, FAR struct tcb_s *pT
|
|||
|
||||
__EXPORT struct system_load_s system_load;
|
||||
|
||||
extern FAR struct _TCB *sched_gettcb(pid_t pid);
|
||||
extern FAR struct tcb_s *sched_gettcb(pid_t pid);
|
||||
|
||||
void cpuload_initialize_once()
|
||||
{
|
||||
|
|
|
@ -54,6 +54,9 @@
|
|||
|
||||
#include "systemlib.h"
|
||||
|
||||
// Didn't seem right to include up_internal.h, so direct extern instead.
|
||||
extern void up_systemreset(void) noreturn_function;
|
||||
|
||||
void
|
||||
systemreset(bool to_bootloader)
|
||||
{
|
||||
|
|
|
@ -46,6 +46,7 @@
|
|||
#include <stdbool.h>
|
||||
#include <unistd.h>
|
||||
#include <fcntl.h>
|
||||
#include <math.h>
|
||||
#include <sys/stat.h>
|
||||
|
||||
#include <arch/board/board.h>
|
||||
|
@ -228,8 +229,8 @@ do_show_print(void *arg, param_t param)
|
|||
if (!(arg == NULL)) {
|
||||
|
||||
/* start search */
|
||||
char *ss = search_string;
|
||||
char *pp = p_name;
|
||||
const char *ss = search_string;
|
||||
const char *pp = p_name;
|
||||
bool mismatch = false;
|
||||
|
||||
/* XXX this comparison is only ok for trailing wildcards */
|
||||
|
|
Loading…
Reference in New Issue