moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
display_random_state.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2012, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34
35/* Author: Ioan Sucan */
36
37#include <chrono>
40
41using namespace std::chrono_literals;
42
43int main(int argc, char** argv)
44{
45 rclcpp::init(argc, argv);
46 auto node = rclcpp::Node::make_shared("display_random_state");
47 moveit::setNodeLoggerName(node->get_name());
48
49 bool valid = false;
50 bool invalid = false;
51 for (int i = 0; i < argc; ++i)
52 {
53 if (strcmp(argv[i], "--valid") == 0)
54 {
55 valid = true;
56 break;
57 }
58 if (strcmp(argv[i], "--invalid") == 0)
59 {
60 invalid = true;
61 break;
62 }
63 }
64
65 rclcpp::executors::MultiThreadedExecutor executor;
66 executor.add_node(node);
67
69 opt.robot_description = "robot_description";
70 auto rml = std::make_shared<robot_model_loader::RobotModelLoader>(node, opt);
74 auto pub_scene = node->create_publisher<moveit_msgs::msg::PlanningScene>("planning_scene", 1);
75
76 rclcpp::sleep_for(500ms);
77
78 do
79 {
80 if (!psm.getPlanningScene())
81 {
82 RCLCPP_ERROR(node->get_logger(), "Planning scene did not load properly, exiting...");
83 break;
84 }
85
86 std::cout << "Type a number and hit Enter. That number of ";
87 if (valid)
88 {
89 std::cout << "valid ";
90 }
91 else if (invalid)
92 {
93 std::cout << "invalid ";
94 }
95 std::cout << "states will be randomly generated at an interval of one second and published as a planning scene."
96 << '\n';
97 std::size_t n;
98 std::cin >> n;
99
100 for (std::size_t i = 0; i < n; ++i)
101 {
102 if (valid)
103 {
104 bool found = false;
105 unsigned int attempts = 0;
106 do
107 {
108 attempts++;
109 psm.getPlanningScene()->getCurrentStateNonConst().setToRandomPositions();
112 psm.getPlanningScene()->checkCollision(req, res);
113 found = !res.collision;
114 } while (!found && attempts < 100);
115 if (!found)
116 {
117 std::cout << "Unable to find valid state" << '\n';
118 continue;
119 }
120 }
121 else if (invalid)
122 {
123 bool found = false;
124 unsigned int attempts = 0;
125 do
126 {
127 attempts++;
128 psm.getPlanningScene()->getCurrentStateNonConst().setToRandomPositions();
131 psm.getPlanningScene()->checkCollision(req, res);
132 found = res.collision;
133 } while (!found && attempts < 100);
134 if (!found)
135 {
136 std::cout << "Unable to find invalid state" << '\n';
137 continue;
138 }
139 }
140 else
141 psm.getPlanningScene()->getCurrentStateNonConst().setToRandomPositions();
142
143 moveit_msgs::msg::PlanningScene psmsg;
144 psm.getPlanningScene()->getPlanningSceneMsg(psmsg);
145 pub_scene->publish(psmsg);
146 std::cout << psm.getPlanningScene()->getCurrentState() << '\n';
147
148 rclcpp::sleep_for(1s);
149 }
150 } while (rclcpp::ok());
151
152 rclcpp::shutdown();
153 return 0;
154}
PlanningSceneMonitor Subscribes to the topic planning_scene.
void startSceneMonitor(const std::string &scene_topic=DEFAULT_PLANNING_SCENE_TOPIC)
Start the scene monitor (ROS topic-based)
void startWorldGeometryMonitor(const std::string &collision_objects_topic=DEFAULT_COLLISION_OBJECT_TOPIC, const std::string &planning_scene_world_topic=DEFAULT_PLANNING_SCENE_WORLD_TOPIC, const bool load_octomap_monitor=true)
Start the OccupancyMapMonitor and listening for:
const planning_scene::PlanningScenePtr & getPlanningScene()
Avoid this function! Returns an unsafe pointer to the current planning scene.
int main(int argc, char **argv)
void setNodeLoggerName(const std::string &name)
Call once after creating a node to initialize logging namespaces.
Definition logger.cpp:73
Representation of a collision checking request.
Representation of a collision checking result.
bool collision
True if collision was found, false otherwise.
Structure that encodes the options to be passed to the RobotModelLoader constructor.
std::string robot_description
The string name corresponding to the ROS param where the URDF is loaded; Using the same parameter nam...