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 < 200 * 30; ++i)
65 clock.clock += clock_step;
66 pub_clock.publish(clock);
72 ASSERT_TRUE(static_cast<bool>(joint_states));
75 trajectory_msgs::JointTrajectory cmd;
76 cmd.header.stamp = clock.clock;
77 cmd.joint_names.resize(1);
78 cmd.joint_names[0] =
"joint0";
81 cmd.points[0].positions.resize(1);
82 cmd.points[0].positions[0] = 1.0;
83 cmd.points[0].velocities.resize(1);
84 cmd.points[0].velocities[0] = 1.0;
88 for (
int i = 0; i < 50; ++i)
90 clock.clock += clock_step;
91 pub_clock.publish(clock);
97 ASSERT_TRUE(static_cast<bool>(joint_states));
98 ASSERT_EQ(joint_states->name.size(), 1u);
99 ASSERT_EQ(joint_states->name[0],
"joint0");
100 ASSERT_EQ(joint_states->velocity.size(), 1u);
101 ASSERT_NEAR(joint_states->velocity[0], 1.0, 0.1)
102 <<
"Valid joint_trajectory must not be ignored";
105 cmd.header.stamp = clock.clock;
106 cmd.points[0].positions[0] = 0.0;
107 cmd.points[0].velocities[0] = 0.0;
110 for (
int i = 0; i < 50; ++i)
112 clock.clock += clock_step;
113 pub_clock.publish(clock);
117 ASSERT_NEAR(joint_states->velocity[0], 0.0, 0.1)
118 <<
"Valid joint_trajectory must not be ignored";
122 cmd.points[0].positions[0] = 1.0;
123 cmd.points[0].velocities[0] = 1.0;
126 for (
int i = 0; i < 50; ++i)
128 clock.clock += clock_step;
129 pub_clock.publish(clock);
133 ASSERT_NEAR(joint_states->velocity[0], 0.0, 0.1)
134 <<
"Outdated joint_trajectory must be ignored";
137 int main(
int argc,
char** argv)
139 testing::InitGoogleTest(&argc, argv);
140 ros::init(argc, argv,
"test_joint_trajectory");
142 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()