Skip to content

Commit

Permalink
Port demo_scene to ROS2
Browse files Browse the repository at this point in the history
  • Loading branch information
JafarAbdi committed Jan 27, 2020
1 parent 4ece1f7 commit 37a5081
Showing 1 changed file with 18 additions and 17 deletions.
35 changes: 18 additions & 17 deletions moveit_ros/planning/planning_scene_monitor/demos/demo_scene.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,13 +37,15 @@
#include <moveit/planning_scene_monitor/planning_scene_monitor.h>
#include <geometric_shapes/solid_primitive_dims.h>

#include <rclcpp/rclcpp.hpp>

static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_ros.planning_scene_monitor.demo_scene");

static const std::string ROBOT_DESCRIPTION = "robot_description";

void sendKnife()
void sendKnife(const rclcpp::Node::SharedPtr& node)
{
ros::NodeHandle nh;
ros::Publisher pub_aco = nh.advertise<moveit_msgs::msg::AttachedCollisionObject>("attached_collision_object", 10);

auto pub_aco = node->create_publisher<moveit_msgs::msg::AttachedCollisionObject>("attached_collision_object", 10);
moveit_msgs::msg::AttachedCollisionObject aco;
aco.link_name = "r_wrist_roll_link";
aco.touch_links.push_back("r_wrist_roll_link");
Expand All @@ -61,37 +63,36 @@ void sendKnife()

moveit_msgs::msg::CollisionObject& co = aco.object;
co.id = "knife";
co.header.stamp = ros::Time::now();
co.header.stamp = rclcpp::Clock().now();
co.header.frame_id = aco.link_name;
co.operation = moveit_msgs::msg::CollisionObject::ADD;
co.primitives.resize(1);
co.primitives[0].type = shape_msgs::SolidPrimitive::BOX;
co.primitives[0].type = shape_msgs::msg::SolidPrimitive::BOX;
co.primitives[0].dimensions.push_back(0.1);
co.primitives[0].dimensions.push_back(0.1);
co.primitives[0].dimensions.push_back(0.4);
co.primitive_poses.resize(1);
co.primitive_poses[0].position.x = 0.1;
co.primitive_poses[0].position.y = 0;
co.primitive_poses[0].position.z = -0.2;
co.primitive_poses[0].orientation.w = 1.0;

pub_aco.publish(aco);
ros::Duration(1).sleep();
pub_aco.publish(aco);
ROS_INFO("Object published.");
ros::Duration(1.5).sleep();
using namespace std::chrono_literals;
pub_aco->publish(aco);
rclcpp::sleep_for(1s);
pub_aco->publish(aco);
RCLCPP_INFO(LOGGER, "Object published.");
rclcpp::sleep_for(1500ms);
}

int main(int argc, char** argv)
{
ros::init(argc, argv, "demo", ros::init_options::AnonymousName);
rclcpp::init(argc, argv);

ros::AsyncSpinner spinner(1);
spinner.start();
auto node = rclcpp::Node::make_shared("demo_scene");

sendKnife();
sendKnife(node);

ros::waitForShutdown();
rclcpp::spin(node);

return 0;
}

0 comments on commit 37a5081

Please sign in to comment.