4 Copyright (c) 2016, Allgeyer Tobias, Aumann Florian, Borella Jocelyn, Hutmacher Robin, Karrenbauer Oliver, Marek Felix, Meissner Pascal, Trautmann Jeremias, Wittenbeck Valerij 8 Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: 10 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. 12 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. 14 3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission. 16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 28 from geometry_msgs.msg
import (Pose, Point, Vector3)
30 from common.evaluation_decorators
import *
31 from visualization_msgs.msg
import Marker
32 from std_msgs.msg
import ColorRGBA
33 import state_acquisition
37 marker_id, last_robot_pose=None):
39 Publishes marker to visualize robot path 42 waypoints = rospy.get_param(
"/scene_exploration_sm/waypoints")
43 publisher = rospy.Publisher(waypoints, Marker, queue_size=10)
45 rospy.logdebug(
"last_robot_pose is: " + str(last_robot_pose))
46 if last_robot_pose
is not None:
47 points.append(Point(last_robot_pose.position.x,
48 last_robot_pose.position.y,
50 points.append(Point(current_robot_pose.position.x,
51 current_robot_pose.position.y,
54 if current_camera_pose
is not None:
55 z_pose = current_camera_pose.position.z
59 center = Point(current_robot_pose.position.x,
60 current_robot_pose.position.y,
62 pose_marker = Marker()
63 pose_marker.header.stamp = rospy.Time.now()
64 pose_marker.header.frame_id =
'/map' 65 pose_marker.ns =
'waypoints_cyl' 66 pose_marker.type = Marker.CYLINDER
67 pose_marker.id = marker_id + 2
68 pose_marker.action = Marker.ADD
69 pose_marker.scale =
Vector3(0.05, 0.05, z_pose)
70 pose_marker.color = ColorRGBA(0, 0, 1, 1)
71 pose_marker.lifetime = rospy.Duration()
72 pose_marker.pose.position = center
76 if last_robot_pose
is None:
77 rospy.loginfo(
"Sleeping till waypoint publisher is ready")
80 publisher.publish(pose_marker)
83 marker.header.stamp = rospy.Time.now()
84 marker.header.frame_id =
'/map' 85 marker.ns =
'waypoints_lines' 86 marker.type = Marker.LINE_LIST
88 marker.action = Marker.ADD
89 marker.scale =
Vector3(0.02, 0.1, 0.1)
90 marker.color = ColorRGBA(0, 1, 1, 1)
91 marker.lifetime = rospy.Duration()
92 marker.points = points
94 publisher.publish(marker)
96 if current_camera_pose
is not None:
98 arrow.header.stamp = rospy.Time.now()
99 arrow.header.frame_id =
'/map' 100 arrow.ns =
'waypoints_arrows' 101 arrow.pose = current_camera_pose
102 arrow.type = Marker.ARROW
103 arrow.id = marker_id + 1
104 arrow.action = Marker.ADD
105 arrow.scale =
Vector3(0.5, 0.02, 0.02)
106 arrow.color = ColorRGBA(1, 1, 0, 1)
107 arrow.lifetime = rospy.Duration()
109 publisher.publish(arrow)
112 global waypoint_marker_id
113 waypoint_marker_id = 0
114 global waypoint_old_pose
115 waypoint_old_pose =
None 119 smach.State.__init__(
121 outcomes=[
'succeeded'])
126 rospy.loginfo(
'Executing VISUALIZE_WAYPOINTS')
127 current_pose = state_acquisition.get_robot_pose_cpp()
128 camera_pose = state_acquisition.get_camera_pose_cpp()
130 global waypoint_marker_id
131 global waypoint_old_pose
133 if (current_pose
and camera_pose):
135 waypoint_marker_id, waypoint_old_pose)
138 rospy.wait_for_service(
'/nbv/trigger_frustum_visualization', timeout=5)
139 update_frustum = rospy.ServiceProxy(
140 '/nbv/trigger_frustum_visualization',
141 TriggerFrustumVisualization)
142 update_frustum(camera_pose)
143 except (rospy.ServiceException, rospy.exceptions.ROSException), e:
144 rospy.logwarn(str(e))
146 waypoint_old_pose = current_pose
147 waypoint_marker_id += 4
def visualize_waypoints(current_robot_pose, current_camera_pose, marker_id, last_robot_pose=None)
def execute(self, userdata)