debug_obstacle_distance_node.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9 
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 
18 #include <string>
19 #include <map>
20 #include <ros/ros.h>
21 #include <visualization_msgs/MarkerArray.h>
22 #include "cob_control_msgs/ObstacleDistance.h"
23 #include "cob_control_msgs/ObstacleDistances.h"
24 
26 {
30 
31  std::string chain_base_link_;
32 
33 public:
34  int init()
35  {
36  if (!nh_.getParam("chain_base_link", this->chain_base_link_))
37  {
38  ROS_ERROR("Failed to get parameter \"chain_base_link\".");
39  return -1;
40  }
41 
42  marker_pub_ = this->nh_.advertise<visualization_msgs::MarkerArray>("obstacle_distance/distance_markers", 1, true);
43  obstacle_distances_sub_ = this->nh_.subscribe("obstacle_distance", 1, &DebugObstacleDistance::obstacleDistancesCallback, this);
44 
45  return 0;
46  }
47 
48 
49  void obstacleDistancesCallback(const cob_control_msgs::ObstacleDistances::ConstPtr& msg)
50  {
51  visualization_msgs::MarkerArray marker_array;
52  std::map<std::string, cob_control_msgs::ObstacleDistance> relevant_obstacle_distances;
53 
54  for (uint32_t i = 0; i < msg->distances.size(); i++)
55  {
56  const std::string id = msg->distances[i].link_of_interest;
57  if (relevant_obstacle_distances.count(id) > 0)
58  {
59  if (relevant_obstacle_distances[id].distance > msg->distances[i].distance)
60  {
61  relevant_obstacle_distances[id] = msg->distances[i];
62  }
63  }
64  else
65  {
66  relevant_obstacle_distances[id] = msg->distances[i];
67  }
68  }
69 
70  for (std::map<std::string, cob_control_msgs::ObstacleDistance>::const_iterator it = relevant_obstacle_distances.begin();
71  it != relevant_obstacle_distances.end(); ++it)
72  {
73  // show distance vector as arrow
74  visualization_msgs::Marker marker_vector;
75  marker_vector.type = visualization_msgs::Marker::ARROW;
76  marker_vector.lifetime = ros::Duration(0.5);
77  marker_vector.action = visualization_msgs::Marker::ADD;
78  marker_vector.ns = it->first;
79  marker_vector.id = 42;
80  marker_vector.header.frame_id = chain_base_link_;
81 
82  marker_vector.scale.x = 0.01;
83  marker_vector.scale.y = 0.05;
84 
85  geometry_msgs::Point start;
86  start.x = it->second.nearest_point_obstacle_vector.x;
87  start.y = it->second.nearest_point_obstacle_vector.y;
88  start.z = it->second.nearest_point_obstacle_vector.z;
89 
90  geometry_msgs::Point end;
91  end.x = it->second.nearest_point_frame_vector.x;
92  end.y = it->second.nearest_point_frame_vector.y;
93  end.z = it->second.nearest_point_frame_vector.z;
94 
95  marker_vector.color.a = 1.0;
96  marker_vector.color.g = 1.0;
97 
98  marker_vector.points.push_back(start);
99  marker_vector.points.push_back(end);
100  marker_array.markers.push_back(marker_vector);
101 
102 
103  // show distance as text
104  visualization_msgs::Marker marker_distance;
105  marker_distance.type = visualization_msgs::Marker::TEXT_VIEW_FACING;
106  marker_distance.lifetime = ros::Duration(0.5);
107  marker_distance.action = visualization_msgs::Marker::ADD;
108  marker_distance.ns = it->first;
109  marker_distance.id = 69;
110  marker_distance.header.frame_id = chain_base_link_;
111  std::stringstream sstream;
112  sstream << std::setprecision(3) << it->second.distance;
113  marker_distance.text = sstream.str();
114 
115  marker_distance.scale.x = 0.1;
116  marker_distance.scale.y = 0.1;
117  marker_distance.scale.z = 0.1;
118 
119  marker_distance.color.a = 1.0;
120  // marker_distance.color.r = 1.0;
121  // marker_distance.color.g = 1.0;
122  // marker_distance.color.b = 1.0;
123  marker_distance.color.r = 0.0;
124  marker_distance.color.g = 0.0;
125  marker_distance.color.b = 0.0;
126 
127  marker_distance.pose.position.x = it->second.nearest_point_frame_vector.x;
128  marker_distance.pose.position.y = it->second.nearest_point_frame_vector.y + 0.05;
129  marker_distance.pose.position.z = it->second.nearest_point_frame_vector.z;
130 
131  marker_array.markers.push_back(marker_distance);
132  }
133 
134  this->marker_pub_.publish(marker_array);
135  }
136 };
137 
138 
139 
140 int main(int argc, char** argv)
141 {
142  ros::init(argc, argv, "debug_obstacle_distance_node");
143 
145  if (dod.init() != 0)
146  {
147  ROS_ERROR("Failed to initialize DebugDistanceManager.");
148  return -1;
149  }
150 
151  ros::spin();
152 }
153 
int main(int argc, char **argv)
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
TFSIMD_FORCE_INLINE tfScalar distance(const Vector3 &v) const
ROSCPP_DECL void spin(Spinner &spinner)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool getParam(const std::string &key, std::string &s) const
#define ROS_ERROR(...)
void obstacleDistancesCallback(const cob_control_msgs::ObstacleDistances::ConstPtr &msg)


cob_obstacle_distance
Author(s): Marco Bezzon
autogenerated on Thu Apr 8 2021 02:39:47