From a1418c56ad015f8ed00658b6c6e640f321e70a35 Mon Sep 17 00:00:00 2001 From: Daniel Agar <daniel@agar.ca> Date: Sun, 4 Jun 2017 12:48:12 -0400 Subject: [PATCH] examples remove extra semicolons --- src/examples/fixedwing_control/CMakeLists.txt | 1 - src/examples/fixedwing_control/main.cpp | 75 ++++++++++++------- src/examples/fixedwing_control/params.c | 29 ------- .../mc_att_control_sim.h | 2 +- src/examples/publisher/publisher_example.h | 2 +- .../rover_steering_control/CMakeLists.txt | 1 - src/examples/segway/CMakeLists.txt | 1 - src/examples/subscriber/subscriber_example.h | 2 +- 8 files changed, 50 insertions(+), 63 deletions(-) diff --git a/src/examples/fixedwing_control/CMakeLists.txt b/src/examples/fixedwing_control/CMakeLists.txt index 0f1dcd70e6..660dbfc400 100644 --- a/src/examples/fixedwing_control/CMakeLists.txt +++ b/src/examples/fixedwing_control/CMakeLists.txt @@ -37,7 +37,6 @@ px4_add_module( STACK_MAX 1300 SRCS main.cpp - params.c DEPENDS platforms__common ) diff --git a/src/examples/fixedwing_control/main.cpp b/src/examples/fixedwing_control/main.cpp index fc235d23e9..a5854638ca 100644 --- a/src/examples/fixedwing_control/main.cpp +++ b/src/examples/fixedwing_control/main.cpp @@ -42,40 +42,31 @@ * @author Lorenz Meier <lm@inf.ethz.ch> */ -#include <px4_config.h> -#include <px4_tasks.h> -#include <stdio.h> -#include <stdlib.h> -#include <string.h> -#include <unistd.h> -#include <fcntl.h> -#include <errno.h> -#include <math.h> +#include "params.h" + #include <poll.h> -#include <time.h> + #include <drivers/drv_hrt.h> -#include <uORB/uORB.h> -#include <uORB/topics/vehicle_global_position.h> +#include <geo/geo.h> +#include <matrix/math.hpp> +#include <px4_config.h> +#include <px4_tasks.h> +#include <systemlib/err.h> +#include <systemlib/param/param.h> +#include <systemlib/perf_counter.h> +#include <systemlib/pid/pid.h> +#include <systemlib/systemlib.h> +#include <uORB/topics/actuator_controls.h> +#include <uORB/topics/manual_control_setpoint.h> +#include <uORB/topics/parameter_update.h> #include <uORB/topics/position_setpoint_triplet.h> #include <uORB/topics/vehicle_attitude.h> -#include <uORB/topics/vehicle_status.h> #include <uORB/topics/vehicle_attitude_setpoint.h> -#include <uORB/topics/manual_control_setpoint.h> -#include <uORB/topics/actuator_controls.h> -#include <uORB/topics/vehicle_rates_setpoint.h> #include <uORB/topics/vehicle_global_position.h> -#include <uORB/topics/parameter_update.h> -#include <systemlib/param/param.h> -#include <systemlib/pid/pid.h> -#include <geo/geo.h> -#include <systemlib/perf_counter.h> -#include <systemlib/systemlib.h> -#include <systemlib/err.h> - -#include <matrix/math.hpp> - -/* process-specific header files */ -#include "params.h" +#include <uORB/topics/vehicle_global_position.h> +#include <uORB/topics/vehicle_rates_setpoint.h> +#include <uORB/topics/vehicle_status.h> +#include <uORB/uORB.h> /* Prototypes */ @@ -112,6 +103,14 @@ int fixedwing_control_thread_main(int argc, char *argv[]); */ static void usage(const char *reason); +int parameters_init(struct param_handles *h); + +/** + * Update all parameters + * + */ +int parameters_update(const struct param_handles *h, struct params *p); + /** * Control roll and pitch angle. * @@ -226,6 +225,26 @@ void control_heading(const struct vehicle_global_position_s *pos, const struct p att_sp->q_d[3] = qd(3); } +int parameters_init(struct param_handles *handles) +{ + /* PID parameters */ + handles->hdng_p = param_find("EXFW_HDNG_P"); + handles->roll_p = param_find("EXFW_ROLL_P"); + handles->pitch_p = param_find("EXFW_PITCH_P"); + + return 0; +} + +int parameters_update(const struct param_handles *handles, struct params *parameters) +{ + param_get(handles->hdng_p, &(parameters->hdng_p)); + param_get(handles->roll_p, &(parameters->roll_p)); + param_get(handles->pitch_p, &(parameters->pitch_p)); + + return 0; +} + + /* Main Thread */ int fixedwing_control_thread_main(int argc, char *argv[]) { diff --git a/src/examples/fixedwing_control/params.c b/src/examples/fixedwing_control/params.c index 88bd5cfcf8..d444ea4185 100644 --- a/src/examples/fixedwing_control/params.c +++ b/src/examples/fixedwing_control/params.c @@ -38,8 +38,6 @@ * Parameters for fixedwing demo */ -#include "params.h" - /* controller parameters, use max. 15 characters for param name! */ /** @@ -56,30 +54,3 @@ PARAM_DEFINE_FLOAT(EXFW_ROLL_P, 0.2f); * */ PARAM_DEFINE_FLOAT(EXFW_PITCH_P, 0.2f); - -int parameters_init(struct param_handles *h); - -/** - * Update all parameters - * - */ -int parameters_update(const struct param_handles *h, struct params *p); - -int parameters_init(struct param_handles *h) -{ - /* PID parameters */ - h->hdng_p = param_find("EXFW_HDNG_P"); - h->roll_p = param_find("EXFW_ROLL_P"); - h->pitch_p = param_find("EXFW_PITCH_P"); - - return 0; -} - -int parameters_update(const struct param_handles *h, struct params *p) -{ - param_get(h->hdng_p, &(p->hdng_p)); - param_get(h->roll_p, &(p->roll_p)); - param_get(h->pitch_p, &(p->pitch_p)); - - return 0; -} diff --git a/src/examples/mc_att_control_multiplatform/mc_att_control_sim.h b/src/examples/mc_att_control_multiplatform/mc_att_control_sim.h index 1d76afb82d..da174d6eb1 100644 --- a/src/examples/mc_att_control_multiplatform/mc_att_control_sim.h +++ b/src/examples/mc_att_control_multiplatform/mc_att_control_sim.h @@ -89,7 +89,7 @@ public: void get_mixer_input(Eigen::Vector4d &motor_inputs); protected: - void vehicle_attitude_setpoint_poll() {}; + void vehicle_attitude_setpoint_poll() {} }; diff --git a/src/examples/publisher/publisher_example.h b/src/examples/publisher/publisher_example.h index 2841320734..6281d39e35 100644 --- a/src/examples/publisher/publisher_example.h +++ b/src/examples/publisher/publisher_example.h @@ -46,7 +46,7 @@ class PublisherExample public: PublisherExample(); - ~PublisherExample() {}; + ~PublisherExample() {} int main(); diff --git a/src/examples/rover_steering_control/CMakeLists.txt b/src/examples/rover_steering_control/CMakeLists.txt index 5a014b216b..5b7ecf0b88 100644 --- a/src/examples/rover_steering_control/CMakeLists.txt +++ b/src/examples/rover_steering_control/CMakeLists.txt @@ -37,7 +37,6 @@ px4_add_module( STACK_MAX 1300 SRCS main.cpp - params.c DEPENDS platforms__common ) diff --git a/src/examples/segway/CMakeLists.txt b/src/examples/segway/CMakeLists.txt index 574eb68628..9508503da3 100644 --- a/src/examples/segway/CMakeLists.txt +++ b/src/examples/segway/CMakeLists.txt @@ -39,7 +39,6 @@ px4_add_module( blocks.cpp segway_main.cpp BlockSegwayController.cpp - params.c DEPENDS platforms__common ) diff --git a/src/examples/subscriber/subscriber_example.h b/src/examples/subscriber/subscriber_example.h index 4fdd236366..fec8a76efc 100644 --- a/src/examples/subscriber/subscriber_example.h +++ b/src/examples/subscriber/subscriber_example.h @@ -48,7 +48,7 @@ class SubscriberExample public: SubscriberExample(); - ~SubscriberExample() {}; + ~SubscriberExample() {} void spin() {_n.spin();} -- GitLab