Skip to content
Snippets Groups Projects
Commit a1418c56 authored by Daniel Agar's avatar Daniel Agar Committed by Nuno Marques
Browse files

examples remove extra semicolons

parent 58268c83
No related branches found
No related tags found
No related merge requests found
......@@ -37,7 +37,6 @@ px4_add_module(
STACK_MAX 1300
SRCS
main.cpp
params.c
DEPENDS
platforms__common
)
......
......@@ -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[])
{
......
......@@ -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;
}
......@@ -89,7 +89,7 @@ public:
void get_mixer_input(Eigen::Vector4d &motor_inputs);
protected:
void vehicle_attitude_setpoint_poll() {};
void vehicle_attitude_setpoint_poll() {}
};
......
......@@ -46,7 +46,7 @@ class PublisherExample
public:
PublisherExample();
~PublisherExample() {};
~PublisherExample() {}
int main();
......
......@@ -37,7 +37,6 @@ px4_add_module(
STACK_MAX 1300
SRCS
main.cpp
params.c
DEPENDS
platforms__common
)
......
......@@ -39,7 +39,6 @@ px4_add_module(
blocks.cpp
segway_main.cpp
BlockSegwayController.cpp
params.c
DEPENDS
platforms__common
)
......
......@@ -48,7 +48,7 @@ class SubscriberExample
public:
SubscriberExample();
~SubscriberExample() {};
~SubscriberExample() {}
void spin() {_n.spin();}
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment