42 #include <moveit_msgs/msg/planning_scene.hpp> 
   48   auto log_time_start = node_->now();
 
   49   ASSERT_TRUE(setupStartClient());
 
   50   auto log_time_end = node_->now();
 
   51   RCLCPP_INFO_STREAM(LOGGER, 
"Setup time: " << (log_time_end - log_time_start).seconds());
 
   61   rclcpp::WallRate publish_loop_rate(test_parameters_->publish_hz);
 
   62   log_time_start = node_->now();
 
   63   size_t iterations = 0;
 
   64   while (!sawTrackedStatus() && iterations++ < test_parameters_->timeout_iterations)
 
   66     auto msg = std::make_unique<control_msgs::msg::JointJog>();
 
   67     msg->header.stamp = node_->now();
 
   68     msg->header.frame_id = 
"panda_link3";
 
   69     msg->joint_names.push_back(
"panda_joint4");
 
   70     msg->velocities.push_back(-1.0);
 
   71     pub_joint_cmd_->publish(std::move(msg));
 
   72     publish_loop_rate.sleep();
 
   75   EXPECT_LT(iterations, test_parameters_->timeout_iterations);
 
   76   log_time_end = node_->now();
 
   77   RCLCPP_INFO_STREAM(LOGGER, 
"Wait for collision: " << (log_time_end - log_time_start).seconds());
 
   85   auto log_time_start = node_->now();
 
   86   ASSERT_TRUE(setupStartClient());
 
   87   auto log_time_end = node_->now();
 
   88   RCLCPP_INFO_STREAM(LOGGER, 
"Setup time: " << (log_time_end - log_time_start).seconds());
 
   94   moveit_msgs::msg::CollisionObject collision_object;
 
   95   collision_object.header.frame_id = 
"panda_link0";
 
   96   collision_object.id = 
"box";
 
   98   shape_msgs::msg::SolidPrimitive box;
 
  100   box.dimensions = { 0.1, 0.4, 0.1 };
 
  102   geometry_msgs::msg::Pose box_pose;
 
  103   box_pose.position.x = 0.4;
 
  104   box_pose.position.y = 0.0;
 
  105   box_pose.position.z = 0.4;
 
  107   collision_object.primitives.push_back(box);
 
  108   collision_object.primitive_poses.push_back(box_pose);
 
  109   collision_object.operation = collision_object.ADD;
 
  111   moveit_msgs::msg::PlanningSceneWorld psw;
 
  112   psw.collision_objects.push_back(collision_object);
 
  114   moveit_msgs::msg::PlanningScene ps;
 
  119   auto scene_pub = node_->create_publisher<moveit_msgs::msg::PlanningScene>(
"/planning_scene", 10);
 
  120   scene_pub->publish(ps);
 
  126   rclcpp::WallRate publish_loop_rate(test_parameters_->publish_hz);
 
  127   log_time_start = node_->now();
 
  128   size_t iterations = 0;
 
  129   while (!sawTrackedStatus() && iterations++ < test_parameters_->timeout_iterations)
 
  131     auto msg = std::make_unique<geometry_msgs::msg::TwistStamped>();
 
  132     msg->header.stamp = node_->now();
 
  133     msg->twist.linear.x = 0.2;
 
  134     pub_twist_cmd_->publish(std::move(msg));
 
  135     publish_loop_rate.sleep();
 
  138   EXPECT_LT(iterations, test_parameters_->timeout_iterations);
 
  139   log_time_end = node_->now();
 
  140   RCLCPP_INFO_STREAM(LOGGER, 
"Wait for collision: " << (log_time_end - log_time_start).seconds());
 
  145 int main(
int argc, 
char** argv)
 
  149   rclcpp::init(argc, argv);
 
  150   ::testing::InitGoogleTest(&argc, argv);
 
  152   int ret = RUN_ALL_TESTS();
 
@ DECELERATE_FOR_COLLISION
 
TEST_F(PoseTrackingFixture, OutgoingMsgTest)
 
int main(int argc, char **argv)