Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #define BOOST_PARAMETER_MAX_ARITY 7
00037 #include "jsk_recognition_utils/geo/polyline.h"
00038 #include <jsk_topic_tools/log_utils.h>
00039 #include <cfloat>
00040
00041 namespace jsk_recognition_utils
00042 {
00043 PolyLine::PolyLine(const std::vector < Eigen::Vector3f > &points) : Line(points[points.size()-1] - points[0], points[0])
00044 {
00045 int n = points.size();
00046 segments.resize(n-1);
00047 for (int i = 0; i < n-1; i++) {
00048 Segment::Ptr ln(new Segment(points[i], points[i+1]));
00049 segments[i] = ln;
00050 }
00051 }
00052
00053 Segment::Ptr PolyLine::at(int index) const
00054 {
00055 return segments.at(index);
00056 }
00057
00058 double PolyLine::distanceWithInfo(const Eigen::Vector3f& from,
00059 Eigen::Vector3f& foot_point,
00060 double& distance_to_goal,
00061 int& foot_index,
00062 double& foot_alpha) const
00063 {
00064 double min_len = DBL_MAX;
00065 Eigen::Vector3f point;
00066 double from_start_to_foot = 0;
00067 double distance_from_start = 0;
00068
00069 for(int i = 0; i < segments.size(); i++) {
00070 double to_goal;
00071 double dist = segments[i]->distanceWithInfo(from, point, to_goal);
00072 if (dist < min_len) {
00073 min_len = dist;
00074 foot_point = point;
00075 foot_index = i;
00076 foot_alpha = (segments[i]->length() - to_goal);
00077 from_start_to_foot = distance_from_start + foot_alpha;
00078 }
00079 distance_from_start += segments[i]->length();
00080 }
00081 distance_to_goal = distance_from_start - from_start_to_foot;
00082 return min_len;
00083 }
00084
00085 double PolyLine::distance(const Eigen::Vector3f& from) const
00086 {
00087 double gl, alp;
00088 int idx;
00089 Eigen::Vector3f p;
00090 distanceWithInfo(from, p, gl, idx, alp);
00091 }
00092
00093 double PolyLine::distance(const Eigen::Vector3f& from,
00094 Eigen::Vector3f& foot_point) const
00095 {
00096 double gl, alp;
00097 int idx;
00098 distanceWithInfo(from, foot_point, gl, idx, alp);
00099 }
00100
00101 void PolyLine::getDirection(int index, Eigen::Vector3f& output) const
00102 {
00103 segments[index]->getDirection(output);
00104 }
00105 Eigen::Vector3f PolyLine::getDirection(int index) const
00106 {
00107 Eigen::Vector3f dir;
00108 getDirection(index, dir);
00109 return dir;
00110 }
00111
00112 double PolyLine::length() const
00113 {
00114 double distance_from_start = 0;
00115 for(int i = 0; i < segments.size(); i++) {
00116 distance_from_start += segments[i]->length();
00117 }
00118 return distance_from_start;
00119 }
00120
00121 PolyLine::Ptr PolyLine::flipPolyLine() const
00122 {
00123 PolyLine::Ptr ret;
00124 return ret;
00125 }
00126
00127 void PolyLine::toMarker(visualization_msgs::Marker& marker) const
00128 {
00129 marker.type = visualization_msgs::Marker::LINE_STRIP;
00130
00131 marker.scale.x = 0.02;
00132 marker.color.a = 1.0;
00133 marker.color.r = 0.0;
00134 marker.color.g = 1.0;
00135 marker.color.b = 1.0;
00136
00137 marker.pose.position.x = 0;
00138 marker.pose.position.y = 0;
00139 marker.pose.position.z = 0;
00140 marker.pose.orientation.x = 0;
00141 marker.pose.orientation.y = 0;
00142 marker.pose.orientation.z = 0;
00143 marker.pose.orientation.w = 1;
00144
00145 marker.points.resize(0);
00146 for(int i = 0; i < segments.size(); i++) {
00147 Eigen::Vector3f p;
00148 segments[i]->getOrigin(p);
00149 geometry_msgs::Point pt;
00150 pt.x = p[0];
00151 pt.y = p[1];
00152 pt.z = p[2];
00153 marker.points.push_back(pt);
00154 }
00155 {
00156 Eigen::Vector3f p;
00157 segments[segments.size() - 1]->getEnd(p);
00158 geometry_msgs::Point pt;
00159 pt.x = p[0];
00160 pt.y = p[1];
00161 pt.z = p[2];
00162 marker.points.push_back(pt);
00163 }
00164 }
00165
00166 std::ostream& operator<<(std::ostream& os, const PolyLine& pl)
00167 {
00168 os << "[" << pl.origin_[0];
00169 os << ", " << pl.origin_[1];
00170 os << ", " << pl.origin_[2] << "]";
00171
00172 for (int i = 0; i < pl.segments.size(); i++) {
00173 Eigen::Vector3f p;
00174 pl.segments[i]->getEnd(p);
00175 os << " -- [" << p[0];
00176 os << ", " << p[1];
00177 os << ", " << p[2] << "]";
00178 }
00179 return os;
00180 }
00181 }