motor_parameter_test.cc
Go to the documentation of this file.
1 #include <gtest/gtest.h>
2 #include <ros/ros.h>
4 
5 TEST(MotorParameterTests, getParamOrDefaultTest) {
7  ASSERT_EQ(5, getParamOrDefault(nh, "getParamOrDefaultTest", 5));
8  int foo;
9  ASSERT_TRUE(nh.getParam("getParamOrDefaultTest", foo));
10  ASSERT_EQ(5, foo);
11 
12  ASSERT_EQ(5, getParamOrDefault(nh, "getParamOrDefaultTest", 10));
13 }
14 
15 TEST(MotorParameterTests, NodeParamTest) {
16  ros::NodeHandle nh;
17  NodeParams np(nh);
18  ASSERT_DOUBLE_EQ(10.0, np.controller_loop_rate);
19  nh.setParam("ubiquity_motor/controller_loop_rate", 50.0);
20  np = NodeParams(nh);
21  ASSERT_DOUBLE_EQ(50.0, np.controller_loop_rate);
22 }
23 
24 TEST(MotorParameterTests, CommsParamsTest) {
25  ros::NodeHandle nh;
26  CommsParams cp(nh);
27  ASSERT_EQ("/dev/ttyS0", cp.serial_port);
28  nh.setParam("ubiquity_motor/serial_port", "/dev/foo");
29  cp = CommsParams(nh);
30  ASSERT_EQ("/dev/foo", cp.serial_port);
31 }
32 
33 int main(int argc, char **argv) {
34  testing::InitGoogleTest(&argc, argv);
35  ros::init(argc, argv, "param_test");
36  return RUN_ALL_TESTS();
37 }
double controller_loop_rate
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
TEST(MotorParameterTests, getParamOrDefaultTest)
T getParamOrDefault(ros::NodeHandle nh, std::string parameter_name, T default_val)
bool getParam(const std::string &key, std::string &s) const
std::string serial_port
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const


ubiquity_motor
Author(s):
autogenerated on Mon Jun 10 2019 15:37:24