34 #include <px4_platform_common/module_params.h> 39 #include <gtest/gtest.h> 54 param_t param = param_handle(px4::params::CP_DIST);
72 float value2 = -1999.f;
77 EXPECT_EQ(42.
f, value2);
85 memset(&message, 0xDEAD,
sizeof(message));
94 ASSERT_TRUE(obstacle_distance_pub !=
nullptr);
97 sub_obstacle_distance.update();
106 EXPECT_EQ(0, memcmp(&message, &obstacle_distance,
sizeof(message)));
static struct vehicle_status_s status
__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.
orb_advert_t orb_advertise(const struct orb_metadata *meta, const void *data)
#define ORB_ID(_name)
Generates a pointer to the uORB metadata structure for a given topic.
TEST_F(ParameterTest, testParamReadWrite)
Vector< float, 6 > f(float t, const Matrix< float, 6, 1 > &, const Matrix< float, 3, 1 > &)
__BEGIN_DECLS typedef void * orb_advert_t
ORB topic advertiser handle.
__EXPORT void param_reset_all(void)
Reset all parameters to their default values.
uint32_t param_t
Parameter handle.