32 #include <rosgraph_msgs/Clock.h> 33 #include <sensor_msgs/JointState.h> 34 #include <trajectory_msgs/JointTrajectory.h> 36 #include <gtest/gtest.h> 38 TEST(JointTrajectory, CommandValidation)
45 nh.
advertise<trajectory_msgs::JointTrajectory>(
"joint_trajectory", 1,
true);
47 nh.
advertise<rosgraph_msgs::Clock>(
"clock", 100);
49 sensor_msgs::JointState::ConstPtr joint_states;
50 const boost::function<void(const sensor_msgs::JointState::ConstPtr &)> cb_joint =
51 [&joint_states](
const sensor_msgs::JointState::ConstPtr &msg) ->
void 56 nh.
subscribe(
"joint_states", 100, cb_joint);
58 rosgraph_msgs::Clock clock;
60 pub_clock.publish(clock);
63 for (
int i = 0; i < 1000; ++i)
72 trajectory_msgs::JointTrajectory cmd;
73 cmd.header.stamp = clock.clock;
74 cmd.joint_names.resize(1);
75 cmd.joint_names[0] =
"joint0";
78 cmd.points[0].positions.resize(1);
79 cmd.points[0].positions[0] = 1.0;
80 cmd.points[0].velocities.resize(1);
81 cmd.points[0].velocities[0] = 1.0;
85 for (
int i = 0; i < 50; ++i)
87 clock.clock += clock_step;
88 pub_clock.publish(clock);
94 ASSERT_TRUE(static_cast<bool>(joint_states));
95 ASSERT_EQ(joint_states->name.size(), 1);
96 ASSERT_EQ(joint_states->name[0],
"joint0");
97 ASSERT_EQ(joint_states->velocity.size(), 1);
98 ASSERT_NEAR(joint_states->velocity[0], 1.0, 0.1)
99 <<
"Valid joint_trajectory must not be ignored";
102 cmd.header.stamp = clock.clock;
103 cmd.points[0].positions[0] = 0.0;
104 cmd.points[0].velocities[0] = 0.0;
107 for (
int i = 0; i < 50; ++i)
109 clock.clock += clock_step;
110 pub_clock.publish(clock);
114 ASSERT_NEAR(joint_states->velocity[0], 0.0, 0.1)
115 <<
"Valid joint_trajectory must not be ignored";
119 cmd.points[0].positions[0] = 1.0;
120 cmd.points[0].velocities[0] = 1.0;
123 for (
int i = 0; i < 50; ++i)
125 clock.clock += clock_step;
126 pub_clock.publish(clock);
130 ASSERT_NEAR(joint_states->velocity[0], 0.0, 0.1)
131 <<
"Outdated joint_trajectory must be ignored";
134 int main(
int argc,
char **argv)
136 testing::InitGoogleTest(&argc, argv);
137 ros::init(argc, argv,
"test_joint_trajectory");
139 return RUN_ALL_TESTS();
TEST(JointTrajectory, CommandValidation)
void publish(const boost::shared_ptr< M > &message) const
int main(int argc, char **argv)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ROSCPP_DECL void spinOnce()