px4params don't search recursively for params

- move controllib_test under controllib
This commit is contained in:
Daniel Agar 2017-06-02 20:06:04 -04:00 committed by Lorenz Meier
parent 0dfd8cd039
commit db816982cd
18 changed files with 87 additions and 94 deletions

View File

@ -14,20 +14,13 @@ class SourceScanner(object):
Scans provided path and passes all found contents to the parser using
parser.Parse method.
"""
extensions1 = tuple([".h"])
extensions2 = tuple([".cpp", ".c"])
extensions1 = tuple([".c"])
for srcdir in srcdirs:
for dirname, dirnames, filenames in os.walk(srcdir):
for filename in filenames:
if filename.endswith(extensions1):
path = os.path.join(dirname, filename)
if not self.ScanFile(path, parser):
return False
for filename in filenames:
if filename.endswith(extensions2):
path = os.path.join(dirname, filename)
if not self.ScanFile(path, parser):
return False
for filename in os.listdir(srcdir):
if filename.endswith(extensions1):
path = os.path.join(srcdir, filename)
if not self.ScanFile(path, parser):
return False
return True
def ScanFile(self, path, parser):

View File

@ -59,7 +59,7 @@ set(config_module_list
#drivers/test_ppm
#lib/rc/rc_tests
#modules/commander/commander_tests
#modules/controllib_test
#lib/controllib/controllib_test
#modules/mavlink/mavlink_tests
#modules/unit_test
#modules/uORB/uORB_tests

View File

@ -79,7 +79,7 @@ set(config_module_list
drivers/test_ppm
#lib/rc/rc_tests
modules/commander/commander_tests
modules/controllib_test
lib/controllib/controllib_test
modules/mavlink/mavlink_tests
modules/mc_pos_control/mc_pos_control_tests
modules/unit_test

View File

@ -81,7 +81,7 @@ set(config_module_list
drivers/test_ppm
modules/commander/commander_tests
modules/mc_pos_control/mc_pos_control_tests
modules/controllib_test
lib/controllib/controllib_test
modules/mavlink/mavlink_tests
modules/unit_test
modules/uORB/uORB_tests

View File

@ -81,7 +81,7 @@ set(config_module_list
#drivers/test_ppm
#lib/rc/rc_tests
#modules/commander/commander_tests
#modules/controllib_test
#lib/controllib/controllib_test
#modules/mavlink/mavlink_tests
#modules/unit_test
#modules/uORB/uORB_tests

View File

@ -80,7 +80,7 @@ set(config_module_list
#lib/rc/rc_tests
modules/commander/commander_tests
modules/mc_pos_control/mc_pos_control_tests
modules/controllib_test
lib/controllib/controllib_test
modules/mavlink/mavlink_tests
modules/unit_test
modules/uORB/uORB_tests

View File

@ -85,7 +85,7 @@ set(config_module_list
drivers/test_ppm
#lib/rc/rc_tests
modules/commander/commander_tests
modules/controllib_test
lib/controllib/controllib_test
modules/mavlink/mavlink_tests
modules/mc_pos_control/mc_pos_control_tests
modules/unit_test

View File

@ -85,7 +85,7 @@ set(config_module_list
drivers/test_ppm
modules/commander/commander_tests
modules/mc_pos_control/mc_pos_control_tests
modules/controllib_test
lib/controllib/controllib_test
modules/mavlink/mavlink_tests
modules/unit_test
modules/uORB/uORB_tests

View File

@ -86,7 +86,7 @@ set(config_module_list
drivers/test_ppm
#lib/rc/rc_tests
modules/commander/commander_tests
modules/controllib_test
lib/controllib/controllib_test
modules/mavlink/mavlink_tests
modules/mc_pos_control/mc_pos_control_tests
modules/unit_test

View File

@ -84,7 +84,7 @@ set(config_module_list
drivers/test_ppm
#lib/rc/rc_tests
modules/commander/commander_tests
modules/controllib_test
lib/controllib/controllib_test
modules/mavlink/mavlink_tests
modules/mc_pos_control/mc_pos_control_tests
modules/unit_test

View File

@ -48,7 +48,7 @@ set(config_module_list
#drivers/test_ppm
lib/rc/rc_tests
modules/commander/commander_tests
modules/controllib_test
lib/controllib/controllib_test
modules/mavlink/mavlink_tests
modules/mc_pos_control/mc_pos_control_tests
modules/unit_test

View File

@ -31,7 +31,7 @@
#
############################################################################
px4_add_module(
MODULE modules__controllib_test
MODULE lib__controllib__controllib_test
MAIN controllib_test
COMPILE_FLAGS
SRCS

View File

@ -39,7 +39,6 @@ px4_add_module(
COMPILE_FLAGS
SRCS
position_estimator_inav_main.cpp
position_estimator_inav_params.cpp
inertial_filter.cpp
DEPENDS
platforms__common

View File

@ -343,72 +343,3 @@ PARAM_DEFINE_FLOAT(INAV_LIDAR_OFF, 0.0f);
* @group Position Estimator INAV
*/
PARAM_DEFINE_INT32(CBRK_NO_VISION, 0);
int inav_parameters_init(struct position_estimator_inav_param_handles *h)
{
h->w_z_baro = param_find("INAV_W_Z_BARO");
h->w_z_gps_p = param_find("INAV_W_Z_GPS_P");
h->w_z_gps_v = param_find("INAV_W_Z_GPS_V");
h->w_z_vision_p = param_find("INAV_W_Z_VIS_P");
h->w_z_lidar = param_find("INAV_W_Z_LIDAR");
h->w_xy_gps_p = param_find("INAV_W_XY_GPS_P");
h->w_xy_gps_v = param_find("INAV_W_XY_GPS_V");
h->w_xy_vision_p = param_find("INAV_W_XY_VIS_P");
h->w_xy_vision_v = param_find("INAV_W_XY_VIS_V");
h->w_mocap_p = param_find("INAV_W_MOC_P");
h->w_xy_flow = param_find("INAV_W_XY_FLOW");
h->w_xy_res_v = param_find("INAV_W_XY_RES_V");
h->w_gps_flow = param_find("INAV_W_GPS_FLOW");
h->w_acc_bias = param_find("INAV_W_ACC_BIAS");
h->flow_k = param_find("INAV_FLOW_K");
h->flow_q_min = param_find("INAV_FLOW_Q_MIN");
h->lidar_err = param_find("INAV_LIDAR_ERR");
h->land_t = param_find("INAV_LAND_T");
h->land_disp = param_find("INAV_LAND_DISP");
h->land_thr = param_find("INAV_LAND_THR");
h->no_vision = param_find("CBRK_NO_VISION");
h->delay_gps = param_find("INAV_DELAY_GPS");
h->flow_module_offset_x = param_find("INAV_FLOW_DIST_X");
h->flow_module_offset_y = param_find("INAV_FLOW_DIST_Y");
h->disable_mocap = param_find("INAV_DISAB_MOCAP");
h->enable_lidar_alt_est = param_find("INAV_LIDAR_EST");
h->lidar_calibration_offset = param_find("INAV_LIDAR_OFF");
h->att_ext_hdg_m = param_find("ATT_EXT_HDG_M");
return 0;
}
int inav_parameters_update(const struct position_estimator_inav_param_handles *h,
struct position_estimator_inav_params *p)
{
param_get(h->w_z_baro, &(p->w_z_baro));
param_get(h->w_z_gps_p, &(p->w_z_gps_p));
param_get(h->w_z_gps_v, &(p->w_z_gps_v));
param_get(h->w_z_vision_p, &(p->w_z_vision_p));
param_get(h->w_z_lidar, &(p->w_z_lidar));
param_get(h->w_xy_gps_p, &(p->w_xy_gps_p));
param_get(h->w_xy_gps_v, &(p->w_xy_gps_v));
param_get(h->w_xy_vision_p, &(p->w_xy_vision_p));
param_get(h->w_xy_vision_v, &(p->w_xy_vision_v));
param_get(h->w_mocap_p, &(p->w_mocap_p));
param_get(h->w_xy_flow, &(p->w_xy_flow));
param_get(h->w_xy_res_v, &(p->w_xy_res_v));
param_get(h->w_gps_flow, &(p->w_gps_flow));
param_get(h->w_acc_bias, &(p->w_acc_bias));
param_get(h->flow_k, &(p->flow_k));
param_get(h->flow_q_min, &(p->flow_q_min));
param_get(h->lidar_err, &(p->lidar_err));
param_get(h->land_t, &(p->land_t));
param_get(h->land_disp, &(p->land_disp));
param_get(h->land_thr, &(p->land_thr));
param_get(h->no_vision, &(p->no_vision));
param_get(h->delay_gps, &(p->delay_gps));
param_get(h->flow_module_offset_x, &(p->flow_module_offset_x));
param_get(h->flow_module_offset_y, &(p->flow_module_offset_y));
param_get(h->disable_mocap, &(p->disable_mocap));
param_get(h->enable_lidar_alt_est, &(p->enable_lidar_alt_est));
param_get(h->lidar_calibration_offset, &(p->lidar_calibration_offset));
param_get(h->att_ext_hdg_m, &(p->att_ext_hdg_m));
return 0;
}

View File

@ -1405,3 +1405,73 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
thread_running = false;
return 0;
}
int inav_parameters_init(struct position_estimator_inav_param_handles *h)
{
h->w_z_baro = param_find("INAV_W_Z_BARO");
h->w_z_gps_p = param_find("INAV_W_Z_GPS_P");
h->w_z_gps_v = param_find("INAV_W_Z_GPS_V");
h->w_z_vision_p = param_find("INAV_W_Z_VIS_P");
h->w_z_lidar = param_find("INAV_W_Z_LIDAR");
h->w_xy_gps_p = param_find("INAV_W_XY_GPS_P");
h->w_xy_gps_v = param_find("INAV_W_XY_GPS_V");
h->w_xy_vision_p = param_find("INAV_W_XY_VIS_P");
h->w_xy_vision_v = param_find("INAV_W_XY_VIS_V");
h->w_mocap_p = param_find("INAV_W_MOC_P");
h->w_xy_flow = param_find("INAV_W_XY_FLOW");
h->w_xy_res_v = param_find("INAV_W_XY_RES_V");
h->w_gps_flow = param_find("INAV_W_GPS_FLOW");
h->w_acc_bias = param_find("INAV_W_ACC_BIAS");
h->flow_k = param_find("INAV_FLOW_K");
h->flow_q_min = param_find("INAV_FLOW_Q_MIN");
h->lidar_err = param_find("INAV_LIDAR_ERR");
h->land_t = param_find("INAV_LAND_T");
h->land_disp = param_find("INAV_LAND_DISP");
h->land_thr = param_find("INAV_LAND_THR");
h->no_vision = param_find("CBRK_NO_VISION");
h->delay_gps = param_find("INAV_DELAY_GPS");
h->flow_module_offset_x = param_find("INAV_FLOW_DIST_X");
h->flow_module_offset_y = param_find("INAV_FLOW_DIST_Y");
h->disable_mocap = param_find("INAV_DISAB_MOCAP");
h->enable_lidar_alt_est = param_find("INAV_LIDAR_EST");
h->lidar_calibration_offset = param_find("INAV_LIDAR_OFF");
h->att_ext_hdg_m = param_find("ATT_EXT_HDG_M");
return 0;
}
int inav_parameters_update(const struct position_estimator_inav_param_handles *h,
struct position_estimator_inav_params *p)
{
param_get(h->w_z_baro, &(p->w_z_baro));
param_get(h->w_z_gps_p, &(p->w_z_gps_p));
param_get(h->w_z_gps_v, &(p->w_z_gps_v));
param_get(h->w_z_vision_p, &(p->w_z_vision_p));
param_get(h->w_z_lidar, &(p->w_z_lidar));
param_get(h->w_xy_gps_p, &(p->w_xy_gps_p));
param_get(h->w_xy_gps_v, &(p->w_xy_gps_v));
param_get(h->w_xy_vision_p, &(p->w_xy_vision_p));
param_get(h->w_xy_vision_v, &(p->w_xy_vision_v));
param_get(h->w_mocap_p, &(p->w_mocap_p));
param_get(h->w_xy_flow, &(p->w_xy_flow));
param_get(h->w_xy_res_v, &(p->w_xy_res_v));
param_get(h->w_gps_flow, &(p->w_gps_flow));
param_get(h->w_acc_bias, &(p->w_acc_bias));
param_get(h->flow_k, &(p->flow_k));
param_get(h->flow_q_min, &(p->flow_q_min));
param_get(h->lidar_err, &(p->lidar_err));
param_get(h->land_t, &(p->land_t));
param_get(h->land_disp, &(p->land_disp));
param_get(h->land_thr, &(p->land_thr));
param_get(h->no_vision, &(p->no_vision));
param_get(h->delay_gps, &(p->delay_gps));
param_get(h->flow_module_offset_x, &(p->flow_module_offset_x));
param_get(h->flow_module_offset_y, &(p->flow_module_offset_y));
param_get(h->disable_mocap, &(p->disable_mocap));
param_get(h->enable_lidar_alt_est, &(p->enable_lidar_alt_est));
param_get(h->lidar_calibration_offset, &(p->lidar_calibration_offset));
param_get(h->att_ext_hdg_m, &(p->att_ext_hdg_m));
return 0;
}