planning_components_tools
src
publish_scene_from_text.cpp
Go to the documentation of this file.
1
/*********************************************************************
2
* Software License Agreement (BSD License)
3
*
4
* Copyright (c) 2013, Ioan A. Sucan
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 Ioan A. Sucan 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 <
moveit/planning_scene_monitor/planning_scene_monitor.h
>
38
39
int
main
(
int
argc,
char
** argv)
40
{
41
ros::init
(argc, argv,
"publish_planning_scene"
,
ros::init_options::AnonymousName
);
42
43
// decide whether to publish the full scene
44
bool
full_scene =
false
;
45
46
// the index of the argument with the filename
47
int
filename_index = 1;
48
if
(argc > 2)
49
if
(strncmp(argv[1],
"--scene"
, 7) == 0)
50
{
51
full_scene =
true
;
52
filename_index = 2;
53
}
54
55
if
(argc > 1)
56
{
57
ros::AsyncSpinner
spinner
(1);
58
spinner
.start();
59
60
ros::NodeHandle
nh;
61
ros::Publisher
pub_scene;
62
if
(full_scene)
63
pub_scene = nh.
advertise
<moveit_msgs::PlanningScene>(
64
planning_scene_monitor::PlanningSceneMonitor::DEFAULT_PLANNING_SCENE_TOPIC
, 1);
65
else
66
pub_scene = nh.
advertise
<moveit_msgs::PlanningSceneWorld>(
67
planning_scene_monitor::PlanningSceneMonitor::DEFAULT_PLANNING_SCENE_WORLD_TOPIC
, 1);
68
69
robot_model_loader::RobotModelLoader::Options
opt;
70
opt.
robot_description_
=
"robot_description"
;
71
opt.load_kinematics_solvers_ =
false
;
72
robot_model_loader::RobotModelLoaderPtr rml(
new
robot_model_loader::RobotModelLoader
(opt));
73
planning_scene::PlanningScene
ps(rml->getModel());
74
75
std::ifstream
f
(argv[filename_index]);
76
if
(ps.
loadGeometryFromStream
(
f
))
77
{
78
ROS_INFO
(
"Publishing geometry from '%s' ..."
, argv[filename_index]);
79
moveit_msgs::PlanningScene ps_msg;
80
ps.
getPlanningSceneMsg
(ps_msg);
81
ps_msg.is_diff =
true
;
82
83
ros::WallDuration
dt(0.5);
84
unsigned
int
attempts = 0;
85
while
(pub_scene.getNumSubscribers() < 1 && ++attempts < 100)
86
dt.
sleep
();
87
88
if
(full_scene)
89
pub_scene.publish(ps_msg);
90
else
91
pub_scene.publish(ps_msg.world);
92
93
ros::Duration
(1).
sleep
();
94
}
95
}
96
else
97
ROS_WARN
(
"A filename was expected as argument. That file should be a text representation of the geometry in a "
98
"planning scene."
);
99
100
ros::shutdown
();
101
return
0;
102
}
ros::init_options::AnonymousName
AnonymousName
ros::WallDuration::sleep
bool sleep() const
ros::Publisher
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
planning_scene::PlanningScene
ros::AsyncSpinner
ros::shutdown
ROSCPP_DECL void shutdown()
robot_model_loader::RobotModelLoader
Definition:
robot_model_loader.h:80
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
f
f
planning_scene::PlanningScene::getPlanningSceneMsg
void getPlanningSceneMsg(moveit_msgs::PlanningScene &scene) const
spinner
void spinner()
robot_model_loader::RobotModelLoader::Options
Structure that encodes the options to be passed to the RobotModelLoader constructor.
Definition:
robot_model_loader.h:84
planning_scene_monitor::PlanningSceneMonitor::DEFAULT_PLANNING_SCENE_WORLD_TOPIC
static const std::string DEFAULT_PLANNING_SCENE_WORLD_TOPIC
Definition:
planning_scene_monitor.h:126
ROS_WARN
#define ROS_WARN(...)
planning_scene_monitor.h
planning_scene::PlanningScene::loadGeometryFromStream
bool loadGeometryFromStream(std::istream &in)
planning_scene_monitor::PlanningSceneMonitor::DEFAULT_PLANNING_SCENE_TOPIC
static const std::string DEFAULT_PLANNING_SCENE_TOPIC
The name of the topic used by default for receiving full planning scenes or planning scene diffs.
Definition:
planning_scene_monitor.h:129
robot_model_loader::RobotModelLoader::Options::robot_description_
std::string robot_description_
The string name corresponding to the ROS param where the URDF is loaded; Using the same parameter nam...
Definition:
robot_model_loader.h:99
main
int main(int argc, char **argv)
Definition:
publish_scene_from_text.cpp:39
ros::Duration::sleep
bool sleep() const
ros::WallDuration
ROS_INFO
#define ROS_INFO(...)
ros::Duration
ros::NodeHandle
planning
Author(s): Ioan Sucan
, Sachin Chitta
autogenerated on Thu Jan 9 2025 03:24:37