19 #include <arpa/inet.h> 20 #include <gtest/gtest.h> 24 #define DELETE_ROS_PARAM(param_name) \ 25 if (ros::param::has(param_name)) \ 27 ros::param::del(param_name); \ 30 #define DELETE_ALL_ROS_PARAMS() \ 31 DELETE_ROS_PARAM("password"); \ 32 DELETE_ROS_PARAM("sensor_ip"); \ 33 DELETE_ROS_PARAM("host_ip"); \ 34 DELETE_ROS_PARAM("host_udp_port"); \ 35 DELETE_ROS_PARAM("angle_start"); \ 36 DELETE_ROS_PARAM("angle_end"); \ 37 DELETE_ROS_PARAM("frame_id"); \ 38 DELETE_ROS_PARAM("skip"); \ 39 DELETE_ROS_PARAM("x_axis_rotation"); 47 : password_(
"ac0d68d033")
49 , host_udp_port_(12345)
50 , sensor_ip_(
"1.2.3.4")
51 , expected_password_(
"admin")
52 , expected_host_ip_(htobe32(inet_network(host_ip_.c_str())))
53 , expected_host_udp_port_(htole32(host_udp_port_))
119 EXPECT_EQ(param_handler.getPassword(), expected_password_);
120 EXPECT_EQ(param_handler.getSensorIP(), sensor_ip_);
121 EXPECT_EQ(param_handler.getHostIP(), expected_host_ip_);
122 EXPECT_EQ(param_handler.getHostUDPPort(), expected_host_udp_port_);
123 EXPECT_EQ(param_handler.getFrameID(), expected_frame_id_);
124 EXPECT_EQ(param_handler.getSkip(), expected_skip_);
125 EXPECT_EQ(param_handler.getAngleStart(), expected_angle_start_);
126 EXPECT_EQ(param_handler.getAngleEnd(), expected_angle_end_);
127 EXPECT_EQ(param_handler.getXAxisRotation(), expected_x_axis_rotation_););
161 std::string frame_id =
"abcdefg";
162 float angle_start = 10.5;
163 float angle_end = 204.7;
164 double x_axis_rotation = 100.3;
171 uint16_t expected_skip = 2;
174 Degree expected_x_axis_rotation(x_axis_rotation);
177 EXPECT_EQ(param_handler.
getPassword(), expected_password_);
178 EXPECT_EQ(param_handler.
getSensorIP(), sensor_ip_);
179 EXPECT_EQ(param_handler.
getHostIP(), expected_host_ip_);
180 EXPECT_EQ(param_handler.
getHostUDPPort(), expected_host_udp_port_);
181 EXPECT_EQ(param_handler.
getFrameID(), frame_id);
182 EXPECT_EQ(param_handler.
getSkip(), expected_skip);
183 EXPECT_EQ(param_handler.
getAngleStart(), expected_angle_start);
184 EXPECT_EQ(param_handler.
getAngleEnd(), expected_angle_end);
219 EXPECT_EQ(static_cast<uint32_t>(0), param_handler.getHostIP()));
391 int main(
int argc,
char** argv)
393 ros::init(argc, argv,
"integrationtest_ros_parameter_handler");
396 testing::InitGoogleTest(&argc, argv);
397 return RUN_ALL_TESTS();
PSENscanInternalAngle getAngleEnd() const
Getter Method for angle_end_.
static const uint16_t DEFAULT_SKIP
TEST_F(ROSInvalidParameterTest, test_invalid_params_x_axis_rotation)
std::string expected_password_
Degree expected_x_axis_rotation_
Class to model angles in degrees from user's perspective.
#define DELETE_ROS_PARAM(param_name)
PSENscanInternalAngle expected_angle_end_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
#define DELETE_ALL_ROS_PARAMS()
static const Degree DEFAULT_X_AXIS_ROTATION(137.5)
Degree getXAxisRotation() const
Getter Method for x_axis_rotation_.
Class for getting ROS-Parameters from the parameter-server.
ROSInvalidParameterTest()
std::string expected_frame_id_
int main(int argc, char **argv)
PSENscanInternalAngle getAngleStart() const
Getter Method for angle_start_.
ROSCPP_DECL void set(const std::string &key, const XmlRpc::XmlRpcValue &v)
ROSParameterHandlerTest()
std::string getSensorIP() const
Getter Method for sensor_ip_.
PSENscanInternalAngle expected_angle_start_
uint16_t getSkip() const
Getter method for skip_.
uint32_t expected_host_ip_
ROSRequiredParameterTest()
ros::NodeHandle node_handle_
uint32_t getHostUDPPort() const
Getter method for host_udp_port_.
uint32_t getHostIP() const
Getter method for host_ip_.
std::string getPassword() const
Getter method for password_.
static const std::string DEFAULT_FRAME_ID
std::string getFrameID() const
Getter method for frame_id_.
Class to model angles in PSENscan internal format (tenth of degrees)
static const PSENscanInternalAngle DEFAULT_ANGLE_END(2750)
static const PSENscanInternalAngle DEFAULT_ANGLE_START(0)
uint32_t expected_host_udp_port_