38 #include <geometric_shapes/solid_primitive_dims.h>
39 #include <rclcpp/clock.hpp>
40 #include <rclcpp/executors.hpp>
41 #include <rclcpp/logger.hpp>
42 #include <rclcpp/logging.hpp>
43 #include <rclcpp/node.hpp>
44 #include <rclcpp/publisher.hpp>
45 #include <rclcpp/qos_event.hpp>
46 #include <rclcpp/time.hpp>
47 #include <rclcpp/utilities.hpp>
49 static const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"moveit_ros.planning_scene_monitor.demo_scene");
51 static const std::string ROBOT_DESCRIPTION =
"robot_description";
55 auto pub_aco = node->create_publisher<moveit_msgs::msg::AttachedCollisionObject>(
"attached_collision_object", 10);
56 moveit_msgs::msg::AttachedCollisionObject aco;
57 aco.link_name =
"r_wrist_roll_link";
58 aco.touch_links.push_back(
"r_wrist_roll_link");
59 aco.touch_links.push_back(
"r_gripper_palm_link");
60 aco.touch_links.push_back(
"r_gripper_led_frame");
61 aco.touch_links.push_back(
"r_gripper_motor_accelerometer_link");
62 aco.touch_links.push_back(
"r_gripper_tool_frame");
63 aco.touch_links.push_back(
"r_gripper_motor_slider_link");
64 aco.touch_links.push_back(
"r_gripper_motor_screw_link");
65 aco.touch_links.push_back(
"r_gripper_l_finger_link");
66 aco.touch_links.push_back(
"r_gripper_l_finger_tip_link");
67 aco.touch_links.push_back(
"r_gripper_r_finger_link");
68 aco.touch_links.push_back(
"r_gripper_r_finger_tip_link");
69 aco.touch_links.push_back(
"r_gripper_l_finger_tip_frame");
71 moveit_msgs::msg::CollisionObject& co = aco.object;
73 co.header.stamp = rclcpp::Clock().now();
74 co.header.frame_id = aco.link_name;
75 co.pose.orientation.w = 1.0;
76 co.operation = moveit_msgs::msg::CollisionObject::ADD;
77 co.primitives.resize(1);
78 co.primitives[0].type = shape_msgs::msg::SolidPrimitive::BOX;
79 co.primitives[0].dimensions.push_back(0.1);
80 co.primitives[0].dimensions.push_back(0.1);
81 co.primitives[0].dimensions.push_back(0.4);
82 co.primitive_poses.resize(1);
83 co.primitive_poses[0].position.x = 0.1;
84 co.primitive_poses[0].position.y = 0;
85 co.primitive_poses[0].position.z = -0.2;
87 using namespace std::chrono_literals;
88 pub_aco->publish(aco);
89 rclcpp::sleep_for(1s);
90 pub_aco->publish(aco);
91 RCLCPP_INFO(LOGGER,
"Object published.");
92 rclcpp::sleep_for(1500ms);
95 int main(
int argc,
char** argv)
97 rclcpp::init(argc, argv);
99 auto node = rclcpp::Node::make_shared(
"demo_scene");
void sendKnife(const rclcpp::Node::SharedPtr &node)
int main(int argc, char **argv)
const rclcpp::Logger LOGGER