visualize_obstacle_distance_node.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *   http://www.apache.org/licenses/LICENSE-2.0
00009 
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016  
00017 
00018 #include <string.h>
00019 #include <map>
00020 #include <ros/ros.h>
00021 #include <visualization_msgs/MarkerArray.h>
00022 #include <cob_control_msgs/ObstacleDistances.h>
00023 
00024 
00025 class DebugObstacleDistance
00026 {
00027 ros::NodeHandle nh_;
00028 ros::Publisher marker_pub_;
00029 ros::Subscriber obstacle_distances_sub_;
00030 
00031 public:
00032 
00033     int init()
00034     {
00035         marker_pub_ = this->nh_.advertise<visualization_msgs::MarkerArray>("obstacle_distance/distance_markers", 1, true);
00036         obstacle_distances_sub_ = this->nh_.subscribe("obstacle_distances", 1, &DebugObstacleDistance::obstacleDistancesCallback, this);
00037 
00038         ros::Duration(1.0).sleep();
00039         ROS_WARN("Debug initialized.");
00040         return 0;
00041     }
00042 
00043 
00044     void obstacleDistancesCallback(const cob_control_msgs::ObstacleDistances::ConstPtr& msg)
00045     {
00046         visualization_msgs::MarkerArray marker_array;
00047 
00048         for(unsigned int i = 0; i < msg->distances.size(); i++)
00049         {
00050             cob_control_msgs::ObstacleDistance info = msg->distances[i];
00051             
00052             //show distance vector as arrow
00053             visualization_msgs::Marker marker_vector;
00054             marker_vector.type = visualization_msgs::Marker::ARROW;
00055             marker_vector.lifetime = ros::Duration();
00056             marker_vector.action = visualization_msgs::Marker::ADD;
00057             marker_vector.ns = "arrows";
00058             marker_vector.id = 2*i;
00059             marker_vector.header.frame_id = info.header.frame_id;
00060 
00061             marker_vector.scale.x = 0.01;
00062             marker_vector.scale.y = 0.05;
00063 
00064             geometry_msgs::Point start;
00065             start.x = info.nearest_point_obstacle_vector.x;
00066             start.y = info.nearest_point_obstacle_vector.y;
00067             start.z = info.nearest_point_obstacle_vector.z;
00068 
00069             geometry_msgs::Point end;
00070             end.x = info.nearest_point_frame_vector.x;
00071             end.y = info.nearest_point_frame_vector.y;
00072             end.z = info.nearest_point_frame_vector.z;
00073 
00074             marker_vector.color.a = 1.0;
00075             marker_vector.color.g = 1.0;
00076 
00077             marker_vector.points.push_back(start);
00078             marker_vector.points.push_back(end);
00079             marker_array.markers.push_back(marker_vector);
00080 
00081 
00082             //show distance as text
00083             visualization_msgs::Marker marker_distance;
00084             marker_distance.type = visualization_msgs::Marker::TEXT_VIEW_FACING;
00085             marker_distance.lifetime = ros::Duration();
00086             marker_distance.action = visualization_msgs::Marker::ADD;
00087             marker_distance.ns = "distances";
00088             marker_distance.id = 2*i+1;
00089             marker_distance.header.frame_id = info.header.frame_id;
00090             marker_distance.text = boost::lexical_cast<std::string>(boost::format("%.3f") % info.distance);
00091 
00092             marker_distance.scale.x = 0.1;
00093             marker_distance.scale.y = 0.1;
00094             marker_distance.scale.z = 0.1;
00095 
00096             marker_distance.color.a = 1.0;
00097             //marker_distance.color.r = 1.0;
00098             //marker_distance.color.g = 1.0;
00099             //marker_distance.color.b = 1.0;
00100             marker_distance.color.r = 0.0;
00101             marker_distance.color.g = 0.0;
00102             marker_distance.color.b = 0.0;
00103 
00104             marker_distance.pose.position.x = info.nearest_point_frame_vector.x;
00105             marker_distance.pose.position.y = info.nearest_point_frame_vector.y + 0.05;
00106             marker_distance.pose.position.z = info.nearest_point_frame_vector.z;
00107 
00108             marker_array.markers.push_back(marker_distance);
00109         }
00110 
00111         marker_pub_.publish(marker_array);
00112     }
00113 };
00114 
00115 int main(int argc, char** argv)
00116 {
00117     ros::init(argc, argv, "debug_obstacle_distance_node");
00118 
00119     DebugObstacleDistance dod;
00120     if (dod.init() != 0)
00121     {
00122         ROS_ERROR("Failed to initialize DebugDistanceManager.");
00123         return -1;
00124     }
00125 
00126     ros::spin();
00127 }
00128 


cob_obstacle_distance_moveit
Author(s): Florian Koehler , Felix Messmer
autogenerated on Thu Jun 6 2019 21:23:10