diff --git a/library/Makefile b/library/Makefile index 086720cb..a8483087 100644 --- a/library/Makefile +++ b/library/Makefile @@ -19,7 +19,9 @@ CC := gcc LINKER := gcc # general compiler flags -WFLAGS := -Wall -Wextra -Werror=float-equal -Wuninitialized -Wunused-variable -Wdouble-promotion +WFLAGS := -Wall -Wextra -Werror=float-equal -Wuninitialized \ + -Wunused-variable -Wdouble-promotion -pedantic -Wmissing-prototypes \ + -Wmissing-declarations -Werror=undef CFLAGS := -g -fPIC -I $(INCLUDEDIR) OPT_FLAGS := -O1 LDFLAGS := -lm -lrt -pthread -shared -Wl,-soname,$(SONAME) diff --git a/library/include/rc/adc.h b/library/include/rc/adc.h index 459e5f7a..33c56445 100644 --- a/library/include/rc/adc.h +++ b/library/include/rc/adc.h @@ -43,7 +43,7 @@ extern "C" { * * @return 0 on success, -1 on failure. */ -int rc_adc_init(); +int rc_adc_init(void); /** * @brief Cleans up the ADC subsystem. @@ -52,7 +52,7 @@ int rc_adc_init(); * * @return 0 on success, -1 on failure. */ -int rc_adc_cleanup(); +int rc_adc_cleanup(void); /** * @brief reads the raw integer ADC value for a particular channel @@ -77,14 +77,14 @@ double rc_adc_read_volt(int ch); * * @return voltage of battery or -1 on failure */ -double rc_adc_batt(); +double rc_adc_batt(void); /** * @brief Reads the voltage of the 9-18v DC jack * * @return Voltage at DC jack or -1 on failure */ -double rc_adc_dc_jack(); +double rc_adc_dc_jack(void); diff --git a/library/include/rc/bmp.h b/library/include/rc/bmp.h index 48057518..45d4aa99 100644 --- a/library/include/rc/bmp.h +++ b/library/include/rc/bmp.h @@ -95,7 +95,7 @@ int rc_bmp_set_sea_level_pressure_pa(double pa); * * @return 0 on success, -1 on failure */ -int rc_bmp_power_off(); +int rc_bmp_power_off(void); /** @@ -116,4 +116,4 @@ int rc_bmp_read(rc_bmp_data_t* data); #endif // RC_BMP_H -/** @} end group Barometer */ \ No newline at end of file +/** @} end group Barometer */ \ No newline at end of file diff --git a/library/include/rc/button.h b/library/include/rc/button.h index 7da92e4f..a91e911f 100644 --- a/library/include/rc/button.h +++ b/library/include/rc/button.h @@ -55,7 +55,7 @@ int rc_button_init(int chip, int pin, char polarity, int debounce_us); * @brief Closes all button handlers. Call at the end of your program * before returning. */ -void rc_button_cleanup(); +void rc_button_cleanup(void); /** diff --git a/library/include/rc/cpu.h b/library/include/rc/cpu.h index 03bffa72..9a2461c5 100644 --- a/library/include/rc/cpu.h +++ b/library/include/rc/cpu.h @@ -53,14 +53,14 @@ int rc_cpu_set_governor(rc_governor_t gov); * * @return frequency in hz */ -int rc_cpu_get_freq(); +int rc_cpu_get_freq(void); /** * @brief Prints the current frequency to the screen. For example "600mhz". * * @return 0 on success or -1 on failure. */ -int rc_cpu_print_freq(); +int rc_cpu_print_freq(void); diff --git a/library/include/rc/deprecated.h b/library/include/rc/deprecated.h index a8d72cc4..943e39fe 100644 --- a/library/include/rc/deprecated.h +++ b/library/include/rc/deprecated.h @@ -20,9 +20,9 @@ extern "C" { -int rc_initialize() __attribute__ ((deprecated)); +int rc_initialize(void) __attribute__ ((deprecated)); -int rc_cleanup() __attribute__ ((deprecated)); +int rc_cleanup(void) __attribute__ ((deprecated)); typedef enum rc_button_state_t { RELEASED, @@ -33,21 +33,21 @@ int rc_set_pause_pressed_func(void (*func)(void)) __attribute__ ((deprecated)); int rc_set_pause_released_func(void (*func)(void)) __attribute__ ((deprecated)); int rc_set_mode_pressed_func(void (*func)(void)) __attribute__ ((deprecated)); int rc_set_mode_released_func(void (*func)(void)) __attribute__ ((deprecated)); -rc_button_state_t rc_get_pause_button() __attribute__ ((deprecated)); -rc_button_state_t rc_get_mode_button() __attribute__ ((deprecated)); +rc_button_state_t rc_get_pause_button(void) __attribute__ ((deprecated)); +rc_button_state_t rc_get_mode_button(void) __attribute__ ((deprecated)); int rc_get_encoder_pos(int ch) __attribute__ ((deprecated)); int rc_set_encoder_pos(int ch, int value) __attribute__ ((deprecated)); -int rc_enable_motors() __attribute__ ((deprecated)); -int rc_disable_motors() __attribute__ ((deprecated)); +int rc_enable_motors(void) __attribute__ ((deprecated)); +int rc_disable_motors(void) __attribute__ ((deprecated)); int rc_set_motor(int motor, float duty) __attribute__ ((deprecated)); int rc_set_motor_all(float duty) __attribute__ ((deprecated)); int rc_set_motor_free_spin(int motor) __attribute__ ((deprecated)); -int rc_set_motor_free_spin_all() __attribute__ ((deprecated)); +int rc_set_motor_free_spin_all(void) __attribute__ ((deprecated)); int rc_set_motor_brake(int motor) __attribute__ ((deprecated)); -int rc_set_motor_brake_all() __attribute__ ((deprecated)); +int rc_set_motor_brake_all(void) __attribute__ ((deprecated)); diff --git a/library/include/rc/dsm.h b/library/include/rc/dsm.h index 02d5c02b..217e5d73 100644 --- a/library/include/rc/dsm.h +++ b/library/include/rc/dsm.h @@ -39,7 +39,7 @@ extern "C" { * * @return 0 on success, -1 on failure */ -int rc_dsm_init(); +int rc_dsm_init(void); /** @@ -48,7 +48,7 @@ int rc_dsm_init(); * @return 0 on success, -1 on failure. 1 if there was a timeout due to user * callback function not returning. */ -int rc_dsm_cleanup(); +int rc_dsm_cleanup(void); /** @@ -94,7 +94,7 @@ double rc_dsm_ch_normalized(int ch); * @return returns 1 if new data is ready to be read by the user. otherwise * returns 0 */ -int rc_dsm_is_new_data(); +int rc_dsm_is_new_data(void); /** @@ -122,7 +122,7 @@ void rc_dsm_set_disconnect_callback(void (*func)(void)); * @return returns 1 if packets are arriving in good health without * timeouts. returns 0 otherwise. */ -int rc_dsm_is_connection_active(); +int rc_dsm_is_connection_active(void); /** @@ -131,7 +131,7 @@ int rc_dsm_is_connection_active(); * @return Returns the number of nanoseconds since the last dsm packet was * received. Return -1 on error or if no packet has ever been received. */ -int64_t rc_dsm_nanos_since_last_packet(); +int64_t rc_dsm_nanos_since_last_packet(void); /** @@ -141,7 +141,7 @@ int64_t rc_dsm_nanos_since_last_packet(); * @return returns 10 or 11 indicating 10-bit or 11-bit resolution returns a * 0 if no packet has been received yet or -1 on error */ -int rc_dsm_resolution(); +int rc_dsm_resolution(void); /** @@ -150,7 +150,7 @@ int rc_dsm_resolution(); * @return Returns number of channels being received, 0 if no packet has * been received yet or -1 on error. */ -int rc_dsm_channels(); +int rc_dsm_channels(void); /** @@ -189,7 +189,7 @@ int rc_dsm_channels(); * * @return 0 on success, -1 on failure */ -int rc_dsm_bind_routine(); +int rc_dsm_bind_routine(void); /** @@ -202,7 +202,7 @@ int rc_dsm_bind_routine(); * * @return 0 on success, -1 on failure */ -int rc_dsm_calibrate_routine(); +int rc_dsm_calibrate_routine(void); #ifdef __cplusplus diff --git a/library/include/rc/encoder.h b/library/include/rc/encoder.h index 1f04f354..434fa113 100644 --- a/library/include/rc/encoder.h +++ b/library/include/rc/encoder.h @@ -33,7 +33,7 @@ extern "C" { * * @return 0 on success or -1 on failure */ -int rc_encoder_init(); +int rc_encoder_init(void); /** * @brief Stops the encoder counters and closes file descriptors. This is @@ -42,7 +42,7 @@ int rc_encoder_init(); * * @return 0 on success or -1 on failure. */ -int rc_encoder_cleanup(); +int rc_encoder_cleanup(void); /** * @brief Reads the current position of an encoder channel. diff --git a/library/include/rc/encoder_eqep.h b/library/include/rc/encoder_eqep.h index 0b971b6d..fc6c19a5 100644 --- a/library/include/rc/encoder_eqep.h +++ b/library/include/rc/encoder_eqep.h @@ -34,7 +34,7 @@ extern "C" { * * @return 0 on success or -1 on failure */ -int rc_encoder_eqep_init(); +int rc_encoder_eqep_init(void); /** * @brief Stops the eQEP encoder counters and closes file descriptors. This @@ -43,7 +43,7 @@ int rc_encoder_eqep_init(); * * @return 0 on success or -1 on failure. */ -int rc_encoder_eqep_cleanup(); +int rc_encoder_eqep_cleanup(void); /** * @brief Reads the current position of an encoder channel. diff --git a/library/include/rc/encoder_pru.h b/library/include/rc/encoder_pru.h index 2734ca6e..9953373a 100644 --- a/library/include/rc/encoder_pru.h +++ b/library/include/rc/encoder_pru.h @@ -35,14 +35,14 @@ extern "C" { * * @return 0 on success or -1 on failure */ -int rc_encoder_pru_init(); +int rc_encoder_pru_init(void); /** * @brief Stops the PRU encoder counter and closes file descriptors. This * is not strictly necessary but is recommended that the user calls this * function at the end of their program. */ -void rc_encoder_pru_cleanup(); +void rc_encoder_pru_cleanup(void); /** * @brief Reads the current position of encoder channel 4. @@ -53,7 +53,7 @@ void rc_encoder_pru_cleanup(); * @return The current position (signed 32-bit integer) or -1 and prints an * error message is there is a problem. */ -int rc_encoder_pru_read(); +int rc_encoder_pru_read(void); /** * @brief Sets the current position of encoder channel 4. Usually for diff --git a/library/include/rc/led.h b/library/include/rc/led.h index 44e565ce..97d2b860 100644 --- a/library/include/rc/led.h +++ b/library/include/rc/led.h @@ -64,7 +64,7 @@ int rc_led_set(rc_led_t led, int value); * This does NOT turn off the LEDs, it is up to the user to leave the LEDs in * the desired state before closing. */ -void rc_led_cleanup(); +void rc_led_cleanup(void); /** @@ -113,7 +113,7 @@ void rc_led_stop_blink(rc_led_t led); * rc_led_stop_blink from a separate thread or signal handler. This will cause * rc_led_blink to return 1 if blinking was stopped mid-way. */ -void rc_led_stop_blink_all(); +void rc_led_stop_blink_all(void); diff --git a/library/include/rc/math/filter.h b/library/include/rc/math/filter.h index be5c0949..fe6e274d 100644 --- a/library/include/rc/math/filter.h +++ b/library/include/rc/math/filter.h @@ -92,7 +92,7 @@ typedef struct rc_filter_t{ * * @return Empty zero-filled rc_filter_t struct */ -rc_filter_t rc_filter_empty(); +rc_filter_t rc_filter_empty(void); /** * @brief Allocate memory for a discrete-time filter & populates it with diff --git a/library/include/rc/math/kalman.h b/library/include/rc/math/kalman.h index de587e89..cdf7af53 100644 --- a/library/include/rc/math/kalman.h +++ b/library/include/rc/math/kalman.h @@ -123,7 +123,7 @@ typedef struct rc_kalman_t { * * @return Empty zero-filled rc_kalman_t struct */ -rc_kalman_t rc_kalman_empty(); +rc_kalman_t rc_kalman_empty(void); /** * @brief Allocates memory for a Kalman filter of given dimensions diff --git a/library/include/rc/math/matrix.h b/library/include/rc/math/matrix.h index 36872a09..ef09a76f 100644 --- a/library/include/rc/math/matrix.h +++ b/library/include/rc/math/matrix.h @@ -49,7 +49,7 @@ typedef struct rc_matrix_t{ * * @return Returns an empty rc_matrix_t */ -rc_matrix_t rc_matrix_empty(); +rc_matrix_t rc_matrix_empty(void); /** * @brief Allocates memory for matrix A to have size rows&cols. diff --git a/library/include/rc/math/other.h b/library/include/rc/math/other.h index 61ba2b90..fe323160 100644 --- a/library/include/rc/math/other.h +++ b/library/include/rc/math/other.h @@ -27,7 +27,7 @@ extern "C" { * * @return random floating point number between -1 and 1 */ -float rc_get_random_float(); +float rc_get_random_float(void); /** * @brief Returns a random double-precision floating point number between @@ -38,7 +38,7 @@ float rc_get_random_float(); * * @return random double-precision floating point number between -1 and 1 */ -double rc_get_random_double(); +double rc_get_random_double(void); /** * @brief Modifies val to be bounded between between min and max. diff --git a/library/include/rc/math/ring_buffer.h b/library/include/rc/math/ring_buffer.h index e9f4b7cd..ac403835 100644 --- a/library/include/rc/math/ring_buffer.h +++ b/library/include/rc/math/ring_buffer.h @@ -49,7 +49,7 @@ typedef struct rc_ringbuf_t { * * @return empty and ready-to-allocate rc_ringbuf_t */ -rc_ringbuf_t rc_ringbuf_empty(); +rc_ringbuf_t rc_ringbuf_empty(void); /** * @brief Allocates memory for a ring buffer and initializes an diff --git a/library/include/rc/math/vector.h b/library/include/rc/math/vector.h index f3ed86b3..1ba86dfe 100644 --- a/library/include/rc/math/vector.h +++ b/library/include/rc/math/vector.h @@ -58,7 +58,7 @@ typedef struct rc_vector_t{ * @return rc_vector_t with no allocated memory and the initialized flag set * to 0. */ -rc_vector_t rc_vector_empty(); +rc_vector_t rc_vector_empty(void); /** * @brief Allocates memory for vector v to have specified length. diff --git a/library/include/rc/mavlink_udp.h b/library/include/rc/mavlink_udp.h index 97c5f084..6854591f 100644 --- a/library/include/rc/mavlink_udp.h +++ b/library/include/rc/mavlink_udp.h @@ -103,7 +103,7 @@ int rc_mav_set_system_id(uint8_t system_id); * * @return 0 on success, -1 on failure */ -int rc_mav_cleanup(); +int rc_mav_cleanup(void); /** @@ -201,7 +201,7 @@ int rc_mav_set_callback_connection_lost(void (*func)(void)); * * @return Returns current connection state. */ -rc_mav_connection_state_t rc_mav_get_connection_state(); +rc_mav_connection_state_t rc_mav_get_connection_state(void); /** @@ -222,7 +222,7 @@ uint8_t rc_mav_get_sys_id_of_last_msg(int msg_id); * @return Returns the system ID on success. Returns -1 on failure, for * example if no message has been received. */ -uint8_t rc_mav_get_sys_id_of_last_msg_any(); +uint8_t rc_mav_get_sys_id_of_last_msg_any(void); /** * @brief Fetches the number of nanoseconds since the last message of type @@ -243,7 +243,7 @@ int64_t rc_mav_ns_since_last_msg(int msg_id); * @return Returns the number of nanoseconds since any message has been * received. Returns -1 on failure, for example if no message has been received. */ -int64_t rc_mav_ns_since_last_msg_any(); +int64_t rc_mav_ns_since_last_msg_any(void); /** * @brief Returns the msg_id of the last received packet. @@ -251,7 +251,7 @@ int64_t rc_mav_ns_since_last_msg_any(); * @return Returns the msg_id of the last received packet. Returns -1 on * failure, for example if no message has been received. */ -int rc_mav_msg_id_of_last_msg(); +int rc_mav_msg_id_of_last_msg(void); /** * @brief Prints to stdout a human-readable name for a message type. diff --git a/library/include/rc/mavlink_udp_helpers.h b/library/include/rc/mavlink_udp_helpers.h index 5d96da60..bba842f4 100644 --- a/library/include/rc/mavlink_udp_helpers.h +++ b/library/include/rc/mavlink_udp_helpers.h @@ -42,7 +42,7 @@ extern "C" { * * @return 0 on success or -1 on failure. */ -int rc_mav_send_heartbeat_abbreviated(); +int rc_mav_send_heartbeat_abbreviated(void); /** * @brief Constructs and sends a heartbeat packet of type diff --git a/library/include/rc/model.h b/library/include/rc/model.h index d8c5e803..f64b1b07 100644 --- a/library/include/rc/model.h +++ b/library/include/rc/model.h @@ -70,7 +70,7 @@ typedef enum rc_model_category_t{ * * @return rc_model_t enum representation of model */ -rc_model_t rc_model(); +rc_model_t rc_model(void); /** @@ -78,21 +78,21 @@ rc_model_t rc_model(); * * @return rc_model_category_t enum representation of categoy */ -rc_model_category_t rc_model_category(); +rc_model_category_t rc_model_category(void); /** * @brief prints to the screen the human-readable version of the model name * with no trailing newline character. */ -void rc_model_print(); +void rc_model_print(void); /** * @brief prints to the screen the human-readable version of the category * name with no trailing newline character. */ -void rc_model_category_print(); +void rc_model_category_print(void); #ifdef __cplusplus diff --git a/library/include/rc/motor.h b/library/include/rc/motor.h index ec0740d1..beab5de5 100644 --- a/library/include/rc/motor.h +++ b/library/include/rc/motor.h @@ -42,7 +42,7 @@ extern "C" { * @return 0 on success, -1 on failure which is usually due to lack of user * permissions to access the gpio and pwm systems. */ -int rc_motor_init(); +int rc_motor_init(void); /** @@ -71,7 +71,7 @@ int rc_motor_init_freq(int pwm_frequency_hz); * * @return 0 on success, -1 on failure. */ -int rc_motor_cleanup(); +int rc_motor_cleanup(void); /** diff --git a/library/include/rc/mpu.h b/library/include/rc/mpu.h index fed76fba..cb891b6b 100644 --- a/library/include/rc/mpu.h +++ b/library/include/rc/mpu.h @@ -242,7 +242,7 @@ typedef struct rc_mpu_data_t{ * * @return Returns an rc_mpu_config_t struct with default settings. */ -rc_mpu_config_t rc_mpu_default_config(); +rc_mpu_config_t rc_mpu_default_config(void); /** * @brief Resets a config struct to defaults. @@ -262,7 +262,7 @@ int rc_mpu_set_config_to_default(rc_mpu_config_t* conf); * * @return 0 on success or -1 on failure. */ -int rc_mpu_power_off(); +int rc_mpu_power_off(void); ///@} end common functions @@ -385,7 +385,7 @@ int rc_mpu_set_dmp_callback(void (*func)(void)); * @return Returns 0 once new data is available, 1 if the MPU is shutting * down due to rc_mpu_power_off, or -1 on error. */ -int rc_mpu_block_until_dmp_data(); +int rc_mpu_block_until_dmp_data(void); /** @@ -394,7 +394,7 @@ int rc_mpu_block_until_dmp_data(); * @return nanoseconds since last interrupt, or -1 if no interrupt received * yet. */ -int64_t rc_mpu_nanos_since_last_dmp_interrupt(); +int64_t rc_mpu_nanos_since_last_dmp_interrupt(void); /** @@ -413,7 +413,7 @@ int rc_mpu_set_tap_callback(void (*func)(int direction, int counter)); * @return Returns 0 once a tap is detected, 1 if the MPU is shutting down * due to rc_mpu_power_off(), or -1 on error. */ -int rc_mpu_block_until_tap(); +int rc_mpu_block_until_tap(void); /** @@ -422,7 +422,7 @@ int rc_mpu_block_until_tap(); * @return nanoseconds since last tap, or -1 if no tap has been detected * yet. */ -int64_t rc_mpu_nanos_since_last_tap(); +int64_t rc_mpu_nanos_since_last_tap(void); ///@} end interrupt-driven DMP mode functions @@ -481,7 +481,7 @@ int rc_mpu_calibrate_accel_routine(rc_mpu_config_t conf); * * @return 1 if calibrated, 0 if not */ -int rc_mpu_is_gyro_calibrated(); +int rc_mpu_is_gyro_calibrated(void); /** @@ -493,7 +493,7 @@ int rc_mpu_is_gyro_calibrated(); * * @return 1 if calibrated, 0 if not */ -int rc_mpu_is_mag_calibrated(); +int rc_mpu_is_mag_calibrated(void); /** @@ -505,7 +505,7 @@ int rc_mpu_is_mag_calibrated(); * * @return 1 if calibrated, 0 if not */ -int rc_mpu_is_accel_calibrated(); +int rc_mpu_is_accel_calibrated(void); diff --git a/library/include/rc/pinmux.h b/library/include/rc/pinmux.h index 2e10cee3..c92f6606 100644 --- a/library/include/rc/pinmux.h +++ b/library/include/rc/pinmux.h @@ -112,7 +112,7 @@ int rc_pinmux_set(int pin, rc_pinmux_mode_t mode); * * @return 0 on success, -1 on failure */ -int rc_pinmux_set_default(); +int rc_pinmux_set_default(void); #ifdef __cplusplus diff --git a/library/include/rc/pru.h b/library/include/rc/pru.h index 24be9f8c..f974b16b 100644 --- a/library/include/rc/pru.h +++ b/library/include/rc/pru.h @@ -44,7 +44,7 @@ int rc_pru_start(int ch, const char* fw_name); * * @return memory pointer on success, NULL on failure */ -volatile uint32_t* rc_pru_shared_mem_ptr(); +volatile uint32_t* rc_pru_shared_mem_ptr(void); /** diff --git a/library/include/rc/pthread.h b/library/include/rc/pthread.h index 003401d7..c46c65e4 100644 --- a/library/include/rc/pthread.h +++ b/library/include/rc/pthread.h @@ -90,7 +90,7 @@ int rc_pthread_set_properties_self(int policy, int priority); * * @return niceness (-20 to 20) or -1 on failure and sets errno */ -int rc_pthread_get_process_niceness(); +int rc_pthread_get_process_niceness(void); /** diff --git a/library/include/rc/servo.h b/library/include/rc/servo.h index 2dc77574..87adf510 100644 --- a/library/include/rc/servo.h +++ b/library/include/rc/servo.h @@ -108,14 +108,14 @@ extern "C" { * * @return 0 on success, -1 on failure */ -int rc_servo_init(); +int rc_servo_init(void); /** * @brief Cleans up servo functionality and turns off the power rail. * * @return 0 on success, -1 on failure */ -void rc_servo_cleanup(); +void rc_servo_cleanup(void); /** * @brief enables or disables the 6V power rail to drive servos. diff --git a/library/include/rc/start_stop.h b/library/include/rc/start_stop.h index d8b9744a..0f99ee36 100644 --- a/library/include/rc/start_stop.h +++ b/library/include/rc/start_stop.h @@ -71,7 +71,7 @@ typedef enum rc_state_t { * * @return current process state */ -rc_state_t rc_get_state(); +rc_state_t rc_get_state(void); /** @@ -90,7 +90,7 @@ void rc_set_state(rc_state_t new_state); * * @return 0 on success, -1 on failure */ -int rc_print_state(); +int rc_print_state(void); /** @@ -102,7 +102,7 @@ int rc_print_state(); * rc_kill_exising_process() to kill that process. Returns -1 if there is some * other problem writing to the file. */ -int rc_make_pid_file(); +int rc_make_pid_file(void); /** @@ -136,7 +136,7 @@ int rc_kill_existing_process(float timeout_s); * @return Returns 0 whether or not the file was actually there. Returns -1 * if there was a file system error. */ -int rc_remove_pid_file(); +int rc_remove_pid_file(void); /** @@ -157,7 +157,7 @@ int rc_remove_pid_file(); * * @return Returns 0 on success or -1 on error */ -int rc_enable_signal_handler(); +int rc_enable_signal_handler(void); /** @@ -167,7 +167,7 @@ int rc_enable_signal_handler(); * * @return Returns 0 on success or -1 on error */ -int rc_disable_signal_handler(); +int rc_disable_signal_handler(void); #ifdef __cplusplus diff --git a/library/include/rc/time.h b/library/include/rc/time.h index 711b66fe..e7af964d 100644 --- a/library/include/rc/time.h +++ b/library/include/rc/time.h @@ -63,7 +63,7 @@ void rc_usleep(unsigned int us); * * @return nanoseconds since epoch */ -uint64_t rc_nanos_since_epoch(); +uint64_t rc_nanos_since_epoch(void); /** @@ -75,7 +75,7 @@ uint64_t rc_nanos_since_epoch(); * * @return nanoseconds since system boot */ -uint64_t rc_nanos_since_boot(); +uint64_t rc_nanos_since_boot(void); /** @@ -90,7 +90,7 @@ uint64_t rc_nanos_since_boot(); * * @return nanoseconds of CPU time since thread started */ -uint64_t rc_nanos_thread_time(); +uint64_t rc_nanos_thread_time(void); /** diff --git a/library/include/rc/version.h b/library/include/rc/version.h index 6e8162eb..169e47c9 100644 --- a/library/include/rc/version.h +++ b/library/include/rc/version.h @@ -34,7 +34,7 @@ extern "C" { * * @return integer representation of the library version */ -unsigned int rc_version(); +unsigned int rc_version(void); /** @@ -42,14 +42,14 @@ unsigned int rc_version(); * * @return const char* string */ -const char* rc_version_string(); +const char* rc_version_string(void); /** * @brief prints a string representation of the current library version to * stdout with no trailing newline character. */ -void rc_version_print(); +void rc_version_print(void); #ifdef __cplusplus diff --git a/library/src/bmp/bmp.c b/library/src/bmp/bmp.c index 5adeabe9..3043310b 100644 --- a/library/src/bmp/bmp.c +++ b/library/src/bmp/bmp.c @@ -156,7 +156,7 @@ int rc_bmp_init(rc_bmp_oversample_t oversample, rc_bmp_filter_t filter) -int rc_bmp_power_off() +int rc_bmp_power_off(void) { // make sure the bus is not currently in use by another thread // do not proceed to prevent interfering with that process @@ -266,7 +266,7 @@ int rc_bmp_read(rc_bmp_data_t* data) } -int rc_set_sea_level_pressure_pa(double pa) +int rc_bmp_set_sea_level_pressure_pa(double pa) { // sanity checks if(rc_bmp280_init_flag==0){ diff --git a/library/src/button.c b/library/src/button.c index abc441be..bc7ce3a5 100644 --- a/library/src/button.c +++ b/library/src/button.c @@ -58,9 +58,9 @@ static int shutdown_flag = 0; /** * poll a gpio edge with debounce check. When the button changes state spawn off - * teh user-defined callback in its own thread. + * the user-defined callback in its own thread. */ -void* poll_thread_func(void* arg) +static void* poll_thread_func(void* arg) { int val, event, chip, pin, pol, debounce; int press_expected_event, release_expected_event; @@ -221,7 +221,7 @@ int rc_button_init(int chip, int pin, char polarity, int debounce_us) } -void rc_button_cleanup() +void rc_button_cleanup(void) { int i,j, ret; // signal threads to close diff --git a/library/src/cpu.c b/library/src/cpu.c index d78d854b..e167ef52 100644 --- a/library/src/cpu.c +++ b/library/src/cpu.c @@ -54,7 +54,7 @@ int rc_cpu_set_governor(rc_governor_t gov) } -int rc_cpu_get_freq() +int rc_cpu_get_freq(void) { int freq; FILE* fd = fopen(CURFREQ_PATH, "r"); @@ -73,7 +73,7 @@ int rc_cpu_get_freq() } -int rc_cpu_print_freq() +int rc_cpu_print_freq(void) { int freq= rc_cpu_get_freq(); if(freq==-1) return -1; diff --git a/library/src/deprecated.c b/library/src/deprecated.c index a671dd06..b1fd45ba 100644 --- a/library/src/deprecated.c +++ b/library/src/deprecated.c @@ -10,7 +10,7 @@ #include -int rc_initialize() +int rc_initialize(void) { // initialize pause and mode buttons if(rc_button_init(RC_BTN_PIN_PAUSE, RC_BTN_POLARITY_NORM_HIGH, @@ -39,7 +39,7 @@ int rc_initialize() return 0; } -int rc_cleanup() +int rc_cleanup(void) { rc_button_cleanup(); rc_encoder_eqep_cleanup(); @@ -88,7 +88,7 @@ int rc_set_mode_released_func(void (*func)(void)){ return rc_button_set_callbacks(RC_BTN_PIN_MODE, mode_pressed_func, mode_released_func); } -rc_button_state_t rc_get_pause_button() +rc_button_state_t rc_get_pause_button(void) { int ret = rc_button_get_state(RC_BTN_PIN_PAUSE); if(ret == RC_BTN_STATE_PRESSED) return PRESSED; @@ -96,7 +96,7 @@ rc_button_state_t rc_get_pause_button() return -1; } -rc_button_state_t rc_get_mode_button() +rc_button_state_t rc_get_mode_button(void) { int ret = rc_button_get_state(RC_BTN_PIN_MODE); if(ret == RC_BTN_STATE_PRESSED) return PRESSED; @@ -117,12 +117,12 @@ int rc_set_encoder_pos(int ch, int value) -int rc_enable_motors() +int rc_enable_motors(void) { return rc_motor_standby(0); } -int rc_disable_motors() +int rc_disable_motors(void) { return rc_motor_standby(1); } @@ -142,7 +142,7 @@ int rc_set_motor_free_spin(int motor) return rc_motor_free_spin(motor); } -int rc_set_motor_free_spin_all() +int rc_set_motor_free_spin_all(void) { return rc_motor_free_spin(0); @@ -154,7 +154,7 @@ int rc_set_motor_brake(int motor) } -int rc_set_motor_brake_all() +int rc_set_motor_brake_all(void) { return rc_motor_brake(0); } \ No newline at end of file diff --git a/library/src/dsm.c b/library/src/dsm.c index 98b2cfbe..c8b72b66 100644 --- a/library/src/dsm.c +++ b/library/src/dsm.c @@ -73,7 +73,8 @@ static int init_flag=0; * * @return { description_of_the_return_value } */ -char* __byte_to_binary(unsigned char c) +#ifdef DEBUG +static char* __byte_to_binary(unsigned char c) { static char b[9]; unsigned char x = (unsigned char)c; //cast to unsigned @@ -85,6 +86,7 @@ char* __byte_to_binary(unsigned char c) } return b; } +#endif /** * This is a blocking function which returns 1 if the user presses ENTER. it @@ -94,7 +96,7 @@ char* __byte_to_binary(unsigned char c) * * @return { description_of_the_return_value } */ -int __continue_or_quit() +static int __continue_or_quit(void) { // set stdin to non-canonical raw mode to capture all button presses fflush(stdin); @@ -133,7 +135,7 @@ int __continue_or_quit() * * @return { description_of_the_return_value } */ -void* __parser_func(__attribute__ ((unused)) void* ptr){ +static void* __parser_func(__attribute__ ((unused)) void* ptr){ uint8_t buf[DSM_PACKET_SIZE]; int i, ret; int new_values[RC_MAX_DSM_CHANNELS]; // hold new values before committing @@ -188,7 +190,8 @@ void* __parser_func(__attribute__ ((unused)) void* ptr){ // last few words in buffer are often all 1's, ignore those if((buf[2*i]!=0xFF) || (buf[(2*i)+1]!=0xFF)){ // grab channel id from first byte assuming 1024 mode - ch_id = (buf[i*2]&0b01111100)>>2; + // 0x7C is 0b01111100 + ch_id = (buf[i*2]&0x7C)>>2; if(ch_id>max_channel_id_1024){ max_channel_id_1024 = ch_id; } @@ -209,7 +212,8 @@ void* __parser_func(__attribute__ ((unused)) void* ptr){ // last few words in buffer are often all 1's, ignore those if((buf[2*i]!=0xFF) || (buf[(2*i)+1]!=0xFF)){ // now grab assuming 2048 mode - ch_id = (buf[i*2]&0b01111000)>>3; + // 0x78 is 0b01111000 + ch_id = (buf[i*2]&0x78)>>3; if(ch_id>max_channel_id_2048){ max_channel_id_2048 = ch_id; } @@ -338,15 +342,18 @@ void* __parser_func(__attribute__ ((unused)) void* ptr){ // grab channel id from first byte // and value from both bytes if(resolution == 1024){ - ch_id = (buf[i*2]&0b01111100)>>2; + // 0x7c is 0b01111100 + ch_id = (buf[i*2]&0x7C)>>2; // grab value from least 11 bytes - value = ((buf[i*2]&0b00000011)<<8) + buf[(2*i)+1]; + value = ((buf[i*2]&0x03)<<8) + buf[(2*i)+1]; value += 989; // shift range so 1500 is neutral } else if(resolution == 2048){ - ch_id = (buf[i*2]&0b01111000)>>3; + // 0x78 is 0b01111000 + ch_id = (buf[i*2]&0x78)>>3; // grab value from least 11 bytes - value = ((buf[i*2]&0b00000111)<<8) + buf[(2*i)+1]; + // 0x07 is 0b00000111 + value = ((buf[i*2]&0x07)<<8) + buf[(2*i)+1]; // extra bit of precision means scale is off by factor of // two, also add 989 to center channels around 1500 value = (value/2) + 989; @@ -424,7 +431,7 @@ void* __parser_func(__attribute__ ((unused)) void* ptr){ * * @return NULL */ -void* __calibration_listen_func(__attribute__ ((unused)) void *ptr) +static void* __calibration_listen_func(__attribute__ ((unused)) void *ptr) { int j, raw; //wait for data to start @@ -475,7 +482,7 @@ void* __calibration_listen_func(__attribute__ ((unused)) void *ptr) } -int rc_dsm_init() +int rc_dsm_init(void) { int i; //if calibration file exists, load it and start spektrum thread @@ -572,7 +579,7 @@ int rc_dsm_init() } -int rc_dsm_cleanup() +int rc_dsm_cleanup(void) { int ret; // just return if not running @@ -633,7 +640,7 @@ double rc_dsm_ch_normalized(int ch) } -int rc_dsm_is_new_data() +int rc_dsm_is_new_data(void) { if(init_flag==0){ fprintf(stderr,"ERROR in rc_dsm_is_new_data, call rc_dsm_init first\n"); @@ -662,7 +669,7 @@ void rc_dsm_set_disconnect_callback(void (*func)(void)) } -int rc_dsm_is_connection_active() +int rc_dsm_is_connection_active(void) { if(init_flag==0){ fprintf(stderr,"ERROR in rc_dsm_is_connection_active, call rc_dsm_init first\n"); @@ -672,7 +679,7 @@ int rc_dsm_is_connection_active() } -int64_t rc_dsm_nanos_since_last_packet(){ +int64_t rc_dsm_nanos_since_last_packet(void){ if(init_flag==0){ fprintf(stderr,"ERROR in rc_dsm_nanos_since_last_packet, call rc_dsm_init first\n"); return -1; @@ -683,7 +690,7 @@ int64_t rc_dsm_nanos_since_last_packet(){ } -int rc_dsm_resolution() +int rc_dsm_resolution(void) { if(init_flag==0){ fprintf(stderr,"ERROR in rc_dsm_resolution, call rc_dsm_init first\n"); @@ -693,7 +700,7 @@ int rc_dsm_resolution() } -int rc_dsm_channels() +int rc_dsm_channels(void) { if(init_flag==0){ fprintf(stderr,"ERROR in rc_dsm_channels, call rc_dsm_init first\n"); @@ -706,7 +713,7 @@ int rc_dsm_channels() -int rc_dsm_bind_routine() +int rc_dsm_bind_routine(void) { int value, delay, i; char c = 0; // for reading user input @@ -842,7 +849,7 @@ int rc_dsm_bind_routine() } -int rc_dsm_calibrate_routine() +int rc_dsm_calibrate_routine(void) { int i,ret; FILE* fd; diff --git a/library/src/encoder.c b/library/src/encoder.c index 6ce71b34..a73b7a9b 100644 --- a/library/src/encoder.c +++ b/library/src/encoder.c @@ -3,11 +3,12 @@ */ #include +#include #include #include -int rc_encoder_init() +int rc_encoder_init(void) { if(rc_encoder_eqep_init()){ fprintf(stderr,"ERROR: failed to run rc_encoder_eqep_init\n"); @@ -20,7 +21,7 @@ int rc_encoder_init() return 0; } -int rc_encoder_cleanup() +int rc_encoder_cleanup(void) { rc_encoder_eqep_cleanup(); rc_encoder_pru_cleanup(); diff --git a/library/src/io/adc.c b/library/src/io/adc.c index c21bc776..67e2006e 100644 --- a/library/src/io/adc.c +++ b/library/src/io/adc.c @@ -35,7 +35,7 @@ static int init_flag = 0; // boolean to check if mem mapped static int fd[CHANNELS]; // file descriptors for 8 channels -int rc_adc_init() +int rc_adc_init(void) { char buf[MAX_BUF]; int i, temp_fd; @@ -55,7 +55,7 @@ int rc_adc_init() return 0; } -int rc_adc_cleanup() +int rc_adc_cleanup(void) { int i; for(i=0;iI2C_MAX_BUS)){ fprintf(stderr,"ERROR: i2c bus must be between 0 & %d\n", I2C_MAX_BUS); @@ -428,7 +428,9 @@ int rc_i2c_get_fd(int bus) { } +#ifdef RC_AUTOPILOT_EXT int rc_i2c_read_data(int bus, uint8_t regAddr, size_t length, uint8_t *data) { return rc_i2c_read_bytes(bus, regAddr, length, data); -} \ No newline at end of file +} +#endif // RC_AUTOPILOT_EXT \ No newline at end of file diff --git a/library/src/io/pwm.c b/library/src/io/pwm.c index 484993e6..926ba5ce 100644 --- a/library/src/io/pwm.c +++ b/library/src/io/pwm.c @@ -53,7 +53,7 @@ static int ssindex[3]; // index given by the kernel to each pwm chip when in mod * * @return 0 on succcess, -1 on failure */ -int __export_channels(int ss) +static int __export_channels(int ss) { int export_fd=0; char buf[MAXBUF]; @@ -142,7 +142,7 @@ int __export_channels(int ss) * * @return 0 on succcess, -1 on failure */ -int __unexport_channels(int ss) +static int __unexport_channels(int ss) { int unexport_fd=0; char buf[MAXBUF]; diff --git a/library/src/led.c b/library/src/led.c index e6a36209..e9cfad74 100644 --- a/library/src/led.c +++ b/library/src/led.c @@ -80,7 +80,7 @@ int rc_led_set(rc_led_t led, int value) return 0; } -void rc_led_cleanup() +void rc_led_cleanup(void) { int i; for(i=0;i #include "algebra_common.h" -rc_kalman_t rc_kalman_empty() +rc_kalman_t rc_kalman_empty(void) { rc_kalman_t kf; // set struct to zeros diff --git a/library/src/math/matrix.c b/library/src/math/matrix.c index 9a76464c..52bb4a08 100644 --- a/library/src/math/matrix.c +++ b/library/src/math/matrix.c @@ -64,7 +64,7 @@ int rc_matrix_alloc(rc_matrix_t* A, int rows, int cols) return -1; } // manually fill in the pointer to each row - for(i=0;id[i]=(double*)(ptr+i*cols*sizeof(double)); + for(i=0;id[i]=(double*)(((char*)ptr) + (i*cols*sizeof(double))); A->rows = rows; A->cols = cols; A->initialized = 1; @@ -115,7 +115,7 @@ int rc_matrix_zeros(rc_matrix_t* A, int rows, int cols) return -1; } // manually fill in the pointer to each row - for(i=0;id[i]=(double*)(ptr+i*cols*sizeof(double)); + for(i=0;id[i]=(double*)(((char*)ptr) + (i*cols*sizeof(double))); A->rows = rows; A->cols = cols; A->initialized = 1; diff --git a/library/src/math/other.c b/library/src/math/other.c index f8b872c8..5c98913f 100644 --- a/library/src/math/other.c +++ b/library/src/math/other.c @@ -22,7 +22,7 @@ typedef union { float f; }rc_int_float_t; -float rc_get_random_float() +float rc_get_random_float(void) { rc_int_float_t new; // get random 32-bit int, mask out all but the mantissa (right 23 bits) @@ -37,7 +37,7 @@ typedef union { double d; }rc_int_double_t; -double rc_get_random_double() +double rc_get_random_double(void) { rc_int_double_t new; // get random 64-bit int, mask out all but the mantissa (right 52 bits) diff --git a/library/src/math/ring_buffer.c b/library/src/math/ring_buffer.c index e53c23eb..434a6d52 100644 --- a/library/src/math/ring_buffer.c +++ b/library/src/math/ring_buffer.c @@ -27,7 +27,7 @@ -rc_ringbuf_t rc_ringbuf_empty() +rc_ringbuf_t rc_ringbuf_empty(void) { rc_ringbuf_t out; // zero-out piecemeal instead of with memset to avoid issues with padding diff --git a/library/src/math/vector.c b/library/src/math/vector.c index aabddf50..c579062f 100644 --- a/library/src/math/vector.c +++ b/library/src/math/vector.c @@ -67,7 +67,7 @@ int rc_vector_free(rc_vector_t* v) } -rc_vector_t rc_vector_empty() +rc_vector_t rc_vector_empty(void) { rc_vector_t out; out.d = NULL; diff --git a/library/src/mavlink_udp.c b/library/src/mavlink_udp.c index b78a21e4..3edefd3b 100644 --- a/library/src/mavlink_udp.c +++ b/library/src/mavlink_udp.c @@ -68,7 +68,6 @@ static int listening_flag=0; // private local function declarations; static uint64_t __us_since_boot(); -static void* __listen_thread_func(); static int __address_init(struct sockaddr_in* address, const char* dest_ip, uint16_t port); int __get_msg_common_checks(int msg_id); @@ -83,7 +82,7 @@ static uint64_t __us_since_boot() } // background thread for handling packets -void* __listen_thread_func() +static void* __listen_thread_func(__attribute__((unused)) void* ptr) { int i; uint64_t time; @@ -287,7 +286,7 @@ int rc_mav_set_system_id(uint8_t sys_id) } -int rc_mav_cleanup() +int rc_mav_cleanup(void) { int ret = 0; if(init_flag==0 || listening_flag==0){ @@ -416,7 +415,7 @@ uint8_t rc_mav_get_sys_id_of_last_msg(int msg_id) return messages[msg_id].sysid; } -uint8_t rc_mav_get_sys_id_of_last_msg_any() +uint8_t rc_mav_get_sys_id_of_last_msg_any(void) { if(init_flag==0){ fprintf(stderr, "ERROR in rc_mav_get_sys_id_of_last_msg_any, call rc_mav_init first\n"); @@ -441,7 +440,7 @@ int64_t rc_mav_ns_since_last_msg(int msg_id) return __us_since_boot()-us_of_last_msg[msg_id]; } -int64_t rc_mav_ns_since_last_msg_any() +int64_t rc_mav_ns_since_last_msg_any(void) { if(init_flag==0){ fprintf(stderr, "ERROR in rc_mav_ns_since_last_msg_any, call rc_mav_init first\n"); @@ -453,7 +452,7 @@ int64_t rc_mav_ns_since_last_msg_any() return __us_since_boot()-us_of_last_msg_any; } -int rc_mav_msg_id_of_last_msg() +int rc_mav_msg_id_of_last_msg(void) { if(init_flag==0){ fprintf(stderr, "ERROR in rc_mav_msg_id_of_last_msg, call rc_mav_init first\n"); @@ -465,7 +464,7 @@ int rc_mav_msg_id_of_last_msg() -int rc_mav_send_heartbeat_abbreviated() +int rc_mav_send_heartbeat_abbreviated(void) { // sanity check mavlink_message_t msg; diff --git a/library/src/model.c b/library/src/model.c index ca9ee5bb..0ddcd55d 100644 --- a/library/src/model.c +++ b/library/src/model.c @@ -23,7 +23,7 @@ static int has_checked = 0; -static void __check_model() +static void __check_model(void) { char c[BUF_SIZE]; int ret; @@ -150,7 +150,7 @@ static void __check_model() } -rc_model_t rc_model() +rc_model_t rc_model(void) { if(has_checked) return current_model; @@ -159,7 +159,7 @@ rc_model_t rc_model() return current_model; } -rc_model_category_t rc_model_category() +rc_model_category_t rc_model_category(void) { if(has_checked) return current_category; @@ -171,7 +171,7 @@ rc_model_category_t rc_model_category() #define caseprint(X) case(X): printf(#X); break; -void rc_model_print() +void rc_model_print(void) { rc_model_t model = rc_model(); @@ -203,7 +203,7 @@ void rc_model_print() return; } -void rc_model_category_print() +void rc_model_category_print(void) { rc_model_category_t category = rc_model_category(); diff --git a/library/src/motor.c b/library/src/motor.c index b2b4f0b7..cf30b0d4 100644 --- a/library/src/motor.c +++ b/library/src/motor.c @@ -58,7 +58,7 @@ static int pwmch[CHANNELS]; -int rc_motor_init() +int rc_motor_init(void) { return rc_motor_init_freq(RC_MOTOR_DEFAULT_PWM_FREQ); } @@ -160,7 +160,7 @@ int rc_motor_init_freq(int pwm_frequency_hz) -int rc_motor_cleanup() +int rc_motor_cleanup(void) { int i; if(!init_flag) return 0; diff --git a/library/src/mpu/mpu.c b/library/src/mpu/mpu.c index 630c2f96..18c15d67 100644 --- a/library/src/mpu/mpu.c +++ b/library/src/mpu/mpu.c @@ -108,22 +108,31 @@ static double startMagYaw = 0.0; /** * functions for internal use only **/ -static int __reset_mpu(); -static int __check_who_am_i(); +static int __reset_mpu(void); +static int __check_who_am_i(void); static int __set_gyro_fsr(rc_mpu_gyro_fsr_t fsr, rc_mpu_data_t* data); static int __set_accel_fsr(rc_mpu_accel_fsr_t, rc_mpu_data_t* data); static int __set_gyro_dlpf(rc_mpu_gyro_dlpf_t dlpf); static int __set_accel_dlpf(rc_mpu_accel_dlpf_t dlpf); static int __init_magnetometer(int cal_mode); -static int __power_off_magnetometer(); +static int __power_off_magnetometer(void); static int __mpu_set_bypass(unsigned char bypass_on); static int __mpu_write_mem(unsigned short mem_addr, unsigned short length, unsigned char *data); static int __mpu_read_mem(unsigned short mem_addr, unsigned short length, unsigned char *data); -static int __dmp_load_motion_driver_firmware(); +static int __dmp_load_motion_driver_firmware(void); static int __dmp_set_orientation(unsigned short orient); static int __dmp_enable_gyro_cal(unsigned char enable); static int __dmp_enable_lp_quat(unsigned char enable); static int __dmp_enable_6x_lp_quat(unsigned char enable); +static int __dmp_set_tap_thresh(unsigned char axis, unsigned short thresh); +static int __dmp_set_tap_axes(unsigned char axis); +static int __dmp_set_tap_count(unsigned char min_taps); +static int __dmp_set_tap_time(unsigned short time); +static int __dmp_set_tap_time_multi(unsigned short time); +static int __dmp_set_shake_reject_thresh(long sf, unsigned short thresh); +static int __dmp_set_shake_reject_time(unsigned short time); +static int __dmp_set_shake_reject_timeout(unsigned short time); +static int __collect_accel_samples(int* avg_raw); static int __mpu_reset_fifo(void); static int __mpu_set_sample_rate(int rate); static int __dmp_set_fifo_rate(unsigned short rate); @@ -131,9 +140,9 @@ static int __dmp_enable_feature(unsigned short mask); static int __mpu_set_dmp_state(unsigned char enable); static int __set_int_enable(unsigned char enable); static int __dmp_set_interrupt_mode(unsigned char mode); -static int __load_gyro_calibration(); -static int __load_mag_calibration(); -static int __load_accel_calibration(); +static int __load_gyro_calibration(void); +static int __load_mag_calibration(void); +static int __load_accel_calibration(void); static int __write_gyro_cal_to_disk(int16_t offsets[3]); static int __write_mag_cal_to_disk(double offsets[3], double scale[3]); static int __write_accel_cal_to_disk(double* center, double* lengths); @@ -143,7 +152,7 @@ static int __data_fusion(rc_mpu_data_t* data); static int __mag_correct_orientation(double mag_vec[3]); -rc_mpu_config_t rc_mpu_default_config() +rc_mpu_config_t rc_mpu_default_config(void) { rc_mpu_config_t conf; @@ -408,7 +417,7 @@ int rc_mpu_read_temp(rc_mpu_data_t* data) } -int __reset_mpu() +int __reset_mpu(void) { // disable the interrupt to prevent it from doing things while we reset imu_shutdown_flag = 1; @@ -431,7 +440,8 @@ int __reset_mpu() } -int __check_who_am_i(){ +int __check_who_am_i(void) +{ uint8_t c; //check the who am i register to make sure the chip is alive if(rc_i2c_read_byte(config.i2c_bus, WHO_AM_I_MPU9250, &c)<0){ @@ -641,7 +651,7 @@ int __init_magnetometer(int cal_mode) } -int __power_off_magnetometer() +int __power_off_magnetometer(void) { rc_i2c_set_device_address(config.i2c_bus, config.i2c_addr); // Enable i2c bypass to allow talking to magnetometer @@ -662,7 +672,7 @@ int __power_off_magnetometer() } -int rc_mpu_power_off() +int rc_mpu_power_off(void) { imu_shutdown_flag = 1; // wait for the interrupt thread to exit if it hasn't already @@ -1028,7 +1038,7 @@ int __mpu_read_mem(unsigned short mem_addr, unsigned short length, unsigned char * * loads pre-compiled firmware binary from invensense onto dmp **/ -int __dmp_load_motion_driver_firmware() +int __dmp_load_motion_driver_firmware(void) { unsigned short ii; unsigned short this_write; @@ -2227,7 +2237,7 @@ int __data_fusion(rc_mpu_data_t* data) * * @return 0 on success, -1 on failure */ -int __load_gyro_calibration() +int __load_gyro_calibration(void) { FILE* fd; uint8_t data[6]; @@ -2286,7 +2296,7 @@ int __load_gyro_calibration() * * @return 0 on success, -1 on failure */ -int __load_mag_calibration() +int __load_mag_calibration(void) { FILE *fd; double x,y,z,sx,sy,sz; @@ -2339,7 +2349,7 @@ int __load_mag_calibration() * * @return 0 on success, -1 on failure */ -int __load_accel_calibration() +int __load_accel_calibration(void) { FILE* fd; uint8_t raw[6] = {0,0,0,0,0,0}; @@ -3216,139 +3226,39 @@ int rc_mpu_calibrate_accel_routine(rc_mpu_config_t conf) } -int rc_mpu_is_gyro_calibrated() +int rc_mpu_is_gyro_calibrated(void) { if(!access(CALIBRATION_DIR GYRO_CAL_FILE, F_OK)) return 1; else return 0; } -int rc_mpu_is_mag_calibrated() +int rc_mpu_is_mag_calibrated(void) { if(!access(CALIBRATION_DIR MAG_CAL_FILE, F_OK)) return 1; else return 0; } -int rc_mpu_is_accel_calibrated() +int rc_mpu_is_accel_calibrated(void) { if(!access(CALIBRATION_DIR ACCEL_CAL_FILE, F_OK)) return 1; else return 0; } -/** - * takes a single row on a rotation matrix and returns the associated scalar for - * use by __inv_orientation_matrix_to_scalar. - * - * @param row The row - * - * @return { description_of_the_return_value } - */ -unsigned short __inv_row_2_scale(signed char row[]) -{ - unsigned short b; - - if (row[0] > 0) - b = 0; - else if (row[0] < 0) - b = 4; - else if (row[1] > 0) - b = 1; - else if (row[1] < 0) - b = 5; - else if (row[2] > 0) - b = 2; - else if (row[2] < 0) - b = 6; - else - b = 7; // error - return b; -} - -/** - * This take in a rotation matrix and returns the corresponding 16 bit short - * which is sent to the DMP to set the orientation. This function is actually - * not used in normal operation and only served to retrieve the orientation - * scalars once to populate the rc_mpu_orientation_t enum during development. - * - * @param mtx The mtx - * - * @return { description_of_the_return_value } - */ -unsigned short __inv_orientation_matrix_to_scalar(signed char mtx[]) -{ - unsigned short scalar; - - scalar = __inv_row_2_scale(mtx); - scalar |= __inv_row_2_scale(mtx + 3) << 3; - scalar |= __inv_row_2_scale(mtx + 6) << 6; - return scalar; -} - -/** - * this function purely serves to print out orientation values and rotation - * matrices which form the rc_imu_orientation_t enum. This is not called inside - * this C file and is not exposed to the user. - */ -void __print_orientation_info() -{ - printf("\n"); - //char mtx[9]; - unsigned short orient; - - // Z-UP (identity matrix) - signed char zup[] = {1,0,0, 0,1,0, 0,0,1}; - orient = __inv_orientation_matrix_to_scalar(zup); - printf("Z-UP: %d\n", orient); - - // Z-down - signed char zdown[] = {-1,0,0, 0,1,0, 0,0,-1}; - orient = __inv_orientation_matrix_to_scalar(zdown); - printf("Z-down: %d\n", orient); - - // X-up - signed char xup[] = {0,0,-1, 0,1,0, 1,0,0}; - orient = __inv_orientation_matrix_to_scalar(xup); - printf("x-up: %d\n", orient); - - // X-down - signed char xdown[] = {0,0,1, 0,1,0, -1,0,0}; - orient = __inv_orientation_matrix_to_scalar(xdown); - printf("x-down: %d\n", orient); - - // Y-up - signed char yup[] = {1,0,0, 0,0,-1, 0,1,0}; - orient = __inv_orientation_matrix_to_scalar(yup); - printf("y-up: %d\n", orient); - - // Y-down - signed char ydown[] = {1,0,0, 0,0,1, 0,-1,0}; - orient = __inv_orientation_matrix_to_scalar(ydown); - printf("y-down: %d\n", orient); - - // X-forward - signed char xforward[] = {0,-1,0, 1,0,0, 0,0,1}; - orient = __inv_orientation_matrix_to_scalar(xforward); - printf("x-forward: %d\n", orient); - - // X-back - signed char xback[] = {0,1,0, -1,0,0, 0,0,1}; - orient = __inv_orientation_matrix_to_scalar(xback); - printf("yx-back: %d\n", orient); -} -int64_t rc_mpu_nanos_since_last_dmp_interrupt() +int64_t rc_mpu_nanos_since_last_dmp_interrupt(void) { if(last_interrupt_timestamp_nanos==0) return -1; return rc_nanos_since_epoch() - last_interrupt_timestamp_nanos; } -int64_t rc_mpu_nanos_since_last_tap() +int64_t rc_mpu_nanos_since_last_tap(void) { if(last_tap_timestamp_nanos==0) return -1; return rc_nanos_since_epoch() - last_tap_timestamp_nanos; } -int rc_mpu_block_until_dmp_data() +int rc_mpu_block_until_dmp_data(void) { if(imu_shutdown_flag!=0){ fprintf(stderr,"ERROR: call to rc_mpu_block_until_dmp_data after shutting down mpu\n"); @@ -3368,7 +3278,7 @@ int rc_mpu_block_until_dmp_data() return 0; } -int rc_mpu_block_until_tap() +int rc_mpu_block_until_tap(void) { if(imu_shutdown_flag!=0){ fprintf(stderr,"ERROR: call to rc_mpu_block_until_tap after shutting down mpu\n"); diff --git a/library/src/mpu/mpu_dev_functions.txt b/library/src/mpu/mpu_dev_functions.txt new file mode 100644 index 00000000..d5b65882 --- /dev/null +++ b/library/src/mpu/mpu_dev_functions.txt @@ -0,0 +1,120 @@ +/** + * @file mpu_dev_functions.c + * + * these functions are not actually part of the library but where used in the + * development of the mpu module. They remain here in case they become useful in + * the future. + * + * I repeat, these are NOT part of the mpu module and are NOT accessible by the + * user. + */ + + + +/** + * takes a single row on a rotation matrix and returns the associated scalar for + * use by __inv_orientation_matrix_to_scalar. + * + * @param row The row + * + * @return { description_of_the_return_value } + */ +/* +static unsigned short __inv_row_2_scale(signed char row[]) +{ + unsigned short b; + + if (row[0] > 0) + b = 0; + else if (row[0] < 0) + b = 4; + else if (row[1] > 0) + b = 1; + else if (row[1] < 0) + b = 5; + else if (row[2] > 0) + b = 2; + else if (row[2] < 0) + b = 6; + else + b = 7; // error + return b; +} +*/ + +/** + * This take in a rotation matrix and returns the corresponding 16 bit short + * which is sent to the DMP to set the orientation. This function is actually + * not used in normal operation and only served to retrieve the orientation + * scalars once to populate the rc_mpu_orientation_t enum during development. + * + * @param mtx The mtx + * + * @return { description_of_the_return_value } + */ +/* +static unsigned short __inv_orientation_matrix_to_scalar(signed char mtx[]) +{ + unsigned short scalar; + + scalar = __inv_row_2_scale(mtx); + scalar |= __inv_row_2_scale(mtx + 3) << 3; + scalar |= __inv_row_2_scale(mtx + 6) << 6; + return scalar; +} +*/ + +/** + * this was a debugging and development function and purely serves to print out + * orientation values and rotation matrices which form the rc_imu_orientation_t + * enum. This is not called inside this C file and is not exposed to the user. + * left here for future reference. + */ +/* +static void __print_orientation_info(void) +{ + printf("\n"); + //char mtx[9]; + unsigned short orient; + + // Z-UP (identity matrix) + signed char zup[] = {1,0,0, 0,1,0, 0,0,1}; + orient = __inv_orientation_matrix_to_scalar(zup); + printf("Z-UP: %d\n", orient); + + // Z-down + signed char zdown[] = {-1,0,0, 0,1,0, 0,0,-1}; + orient = __inv_orientation_matrix_to_scalar(zdown); + printf("Z-down: %d\n", orient); + + // X-up + signed char xup[] = {0,0,-1, 0,1,0, 1,0,0}; + orient = __inv_orientation_matrix_to_scalar(xup); + printf("x-up: %d\n", orient); + + // X-down + signed char xdown[] = {0,0,1, 0,1,0, -1,0,0}; + orient = __inv_orientation_matrix_to_scalar(xdown); + printf("x-down: %d\n", orient); + + // Y-up + signed char yup[] = {1,0,0, 0,0,-1, 0,1,0}; + orient = __inv_orientation_matrix_to_scalar(yup); + printf("y-up: %d\n", orient); + + // Y-down + signed char ydown[] = {1,0,0, 0,0,1, 0,-1,0}; + orient = __inv_orientation_matrix_to_scalar(ydown); + printf("y-down: %d\n", orient); + + // X-forward + signed char xforward[] = {0,-1,0, 1,0,0, 0,0,1}; + orient = __inv_orientation_matrix_to_scalar(xforward); + printf("x-forward: %d\n", orient); + + // X-back + signed char xback[] = {0,1,0, -1,0,0, 0,0,1}; + orient = __inv_orientation_matrix_to_scalar(xback); + printf("yx-back: %d\n", orient); +} +*/ \ No newline at end of file diff --git a/library/src/pinmux.c b/library/src/pinmux.c index 9c113b1c..f333143f 100644 --- a/library/src/pinmux.c +++ b/library/src/pinmux.c @@ -326,7 +326,7 @@ int rc_pinmux_set(int pin, rc_pinmux_mode_t mode) } -int rc_pinmux_set_default() +int rc_pinmux_set_default(void) { int ret = 0; // bb blue available pinmux diff --git a/library/src/pru/encoder_pru.c b/library/src/pru/encoder_pru.c index ff6bd272..f2e72032 100644 --- a/library/src/pru/encoder_pru.c +++ b/library/src/pru/encoder_pru.c @@ -20,7 +20,7 @@ static volatile unsigned int* shared_mem_32bit_ptr = NULL; static int init_flag=0; -int rc_encoder_pru_init() +int rc_encoder_pru_init(void) { int i; // map memory @@ -56,7 +56,7 @@ int rc_encoder_pru_init() } -void rc_encoder_pru_cleanup() +void rc_encoder_pru_cleanup(void) { // zero out shared memory if(shared_mem_32bit_ptr != NULL){ @@ -69,7 +69,7 @@ void rc_encoder_pru_cleanup() } -int rc_encoder_pru_read() +int rc_encoder_pru_read(void) { if(shared_mem_32bit_ptr==NULL || init_flag==0){ fprintf(stderr, "ERROR in rc_encoder_pru_read, call rc_encoder_pru_init first\n"); diff --git a/library/src/pru/pru.c b/library/src/pru/pru.c index 738ae5d4..b7ec26f0 100644 --- a/library/src/pru/pru.c +++ b/library/src/pru/pru.c @@ -115,7 +115,7 @@ int rc_pru_start(int ch, const char* fw_name) } -volatile uint32_t* rc_pru_shared_mem_ptr() +volatile uint32_t* rc_pru_shared_mem_ptr(void) { int fd; volatile unsigned int* map; diff --git a/library/src/pru/servo.c b/library/src/pru/servo.c index 9ef522cf..e9b3c699 100644 --- a/library/src/pru/servo.c +++ b/library/src/pru/servo.c @@ -27,7 +27,7 @@ static int init_flag=0; static int esc_max_us = RC_ESC_DEFAULT_MAX_US; static int esc_min_us = RC_ESC_DEFAULT_MIN_US; -int rc_servo_init() +int rc_servo_init(void) { int i; // start gpio power rail pin @@ -72,7 +72,7 @@ int rc_servo_init() } -void rc_servo_cleanup() +void rc_servo_cleanup(void) { int i; // zero out shared memory diff --git a/library/src/pthread.c b/library/src/pthread.c index e9968cd3..cbbd7bd2 100644 --- a/library/src/pthread.c +++ b/library/src/pthread.c @@ -165,7 +165,7 @@ int rc_pthread_set_properties_self(int policy, int priority) -int rc_pthread_get_process_niceness() +int rc_pthread_get_process_niceness(void) { int which = PRIO_PROCESS; id_t pid; diff --git a/library/src/start_stop.c b/library/src/start_stop.c index 981edd6c..16073a61 100644 --- a/library/src/start_stop.c +++ b/library/src/start_stop.c @@ -25,7 +25,7 @@ static void shutdown_signal_handler(int signum); static void segfault_handler(int signum, siginfo_t *info, void *context); -rc_state_t rc_get_state() +rc_state_t rc_get_state(void) { return rc_state; } @@ -38,7 +38,7 @@ void rc_set_state(rc_state_t new_state) } -int rc_print_state() +int rc_print_state(void) { switch(rc_state){ case UNINITIALIZED: @@ -61,7 +61,7 @@ int rc_print_state() } -int rc_make_pid_file() +int rc_make_pid_file(void) { FILE *fd; DIR* dir; @@ -203,7 +203,7 @@ int rc_kill_existing_process(float timeout_s) } -int rc_remove_pid_file() +int rc_remove_pid_file(void) { // if PID file exists, remove it if(access(RC_PID_FILE, F_OK ) == 0) return remove(RC_PID_FILE); @@ -211,7 +211,7 @@ int rc_remove_pid_file() } -int rc_enable_signal_handler() +int rc_enable_signal_handler(void) { // make the sigaction struct for shutdown signals struct sigaction action; @@ -244,7 +244,7 @@ int rc_enable_signal_handler() } -int rc_disable_signal_handler() +int rc_disable_signal_handler(void) { // reset all to defaults struct sigaction action; diff --git a/library/src/time.c b/library/src/time.c index b967c4cf..26647144 100644 --- a/library/src/time.c +++ b/library/src/time.c @@ -37,19 +37,19 @@ void rc_usleep(unsigned int us){ return; } -uint64_t rc_nanos_since_epoch(){ +uint64_t rc_nanos_since_epoch(void){ struct timespec ts; clock_gettime(CLOCK_REALTIME, &ts); return ((uint64_t)ts.tv_sec*1000000000)+ts.tv_nsec; } -uint64_t rc_nanos_since_boot(){ +uint64_t rc_nanos_since_boot(void){ struct timespec ts; clock_gettime(CLOCK_MONOTONIC, &ts); return ((uint64_t)ts.tv_sec*1000000000)+ts.tv_nsec; } -uint64_t rc_nanos_thread_time(){ +uint64_t rc_nanos_thread_time(void){ struct timespec ts; clock_gettime(CLOCK_THREAD_CPUTIME_ID, &ts); return ((uint64_t)ts.tv_sec*1000000000)+ts.tv_nsec; diff --git a/library/src/version.c b/library/src/version.c index 5a4f8739..af534ded 100644 --- a/library/src/version.c +++ b/library/src/version.c @@ -13,18 +13,18 @@ RC_STRINGIFY(RC_LIB_VERSION_PATCH) -unsigned int rc_version() +unsigned int rc_version(void) { return RC_LIB_VERSION_HEX; } -const char* rc_version_string() +const char* rc_version_string(void) { return RC_LIB_VERSION_STRING; } -void rc_version_print() +void rc_version_print(void) { printf(RC_LIB_VERSION_STRING); return;