39 #include <px4_platform_common/posix.h> 40 #include <px4_platform_common/time.h> 41 #include <px4_platform_common/defines.h> 58 bool changed = sub_man.updated();
68 float roll_trim_active;
70 float pitch_trim_active;
72 float yaw_trim_active;
86 float p = sp.y * roll_scale + roll_trim_active;
92 p = -sp.x * pitch_scale + pitch_trim_active;
94 p = sp.r * yaw_scale + yaw_trim_active;
97 if (p1r != 0 || p2r != 0 || p3r != 0) {
#define mavlink_log_info(_pub, _text,...)
Send a mavlink info message (not printed to console).
static orb_advert_t * mavlink_log_pub
#define mavlink_log_critical(_pub, _text,...)
Send a mavlink critical message and print to console.
__EXPORT int param_get(param_t param, void *val)
Copy the value of a parameter.
__EXPORT int param_set(param_t param, const void *val)
Set the value of a parameter.
Global flash based parameter store.
#define ORB_ID(_name)
Generates a pointer to the uORB metadata structure for a given topic.
Commander helper functions definitions.
int do_trim_calibration(orb_advert_t *mavlink_log_pub)
Simple error/warning functions, heavily inspired by the BSD functions of the same names...
__BEGIN_DECLS typedef void * orb_advert_t
ORB topic advertiser handle.
__EXPORT param_t param_find(const char *name)
Look up a parameter by name.
Remote Control calibration routine.