hiep sua ten file
This commit is contained in:
@@ -7,9 +7,9 @@
|
||||
// #include <deque>
|
||||
// #include <iostream>
|
||||
|
||||
#include <nav_msgs/Path.h>
|
||||
#include <robot_nav_msgs/Path.h>
|
||||
#include <robot_geometry_msgs/Point.h>
|
||||
#include <visualization_msgs/Marker.h>
|
||||
#include <robot_visualization_msgs/Marker.h>
|
||||
#include "custom_planner/color.h"
|
||||
|
||||
struct Spline_Inf
|
||||
@@ -47,12 +47,12 @@ class Curve_common
|
||||
{
|
||||
public:
|
||||
Curve_common();
|
||||
nav_msgs::Path Generate_Line(robot_geometry_msgs::Point start_point, robot_geometry_msgs::Point end_point, double t_intervel, std::string frame_id);
|
||||
nav_msgs::Path Generate_BezierCurve(EigenTrajectoryPoint::Vector control_point, double t_intervel, std::string frame_id);
|
||||
nav_msgs::Path Generate_BsplineCurve(Spline_Inf bspline_inf, double t_intervel, std::string frame_id);
|
||||
nav_msgs::Path Generate_NURBSCurve(Spline_Inf spline_inf, double t_intervel, std::string frame_id);
|
||||
nav_msgs::Path Generate_DerivativeBsplineCurve(Spline_Inf bspline_inf, int differential_times, double t_intervel, std::string frame_id);
|
||||
nav_msgs::Path Generate_DerivativeBasisFuncCurve(Spline_Inf bspline_inf, int differential_times, int index, double t_intervel, std::string frame_id);
|
||||
robot_nav_msgs::Path Generate_Line(robot_geometry_msgs::Point start_point, robot_geometry_msgs::Point end_point, double t_intervel, std::string frame_id);
|
||||
robot_nav_msgs::Path Generate_BezierCurve(EigenTrajectoryPoint::Vector control_point, double t_intervel, std::string frame_id);
|
||||
robot_nav_msgs::Path Generate_BsplineCurve(Spline_Inf bspline_inf, double t_intervel, std::string frame_id);
|
||||
robot_nav_msgs::Path Generate_NURBSCurve(Spline_Inf spline_inf, double t_intervel, std::string frame_id);
|
||||
robot_nav_msgs::Path Generate_DerivativeBsplineCurve(Spline_Inf bspline_inf, int differential_times, double t_intervel, std::string frame_id);
|
||||
robot_nav_msgs::Path Generate_DerivativeBasisFuncCurve(Spline_Inf bspline_inf, int differential_times, int index, double t_intervel, std::string frame_id);
|
||||
|
||||
void CalculateDerivativeBasisFunc(Spline_Inf *spline_inf, double u_data, int differential_times);
|
||||
robot_geometry_msgs::Point CalculateDerivativeCurvePoint(Spline_Inf *spline_inf, double u_data, int differential_times, bool UsingNURBS);
|
||||
@@ -67,15 +67,15 @@ class Curve_common
|
||||
void ReadSplineInf(Spline_Inf *bspline_inf, std::vector<double> weight_vector, bool use_limit_derivative_fitting);
|
||||
void ReadDiscreate2DPointFromLaunch(EigenTrajectoryPoint::Vector *input_point, std::vector<double> file_discreate_point);
|
||||
void ReadDiscreate2DPointFromLaunch(std::vector<Eigen::Vector3d, Eigen::aligned_allocator<Eigen::Vector3d> > *input_point, std::vector<double> file_discreate_point);
|
||||
void ShowDiscreatePoint(visualization_msgs::Marker *points, EigenTrajectoryPoint::Vector discreate_point);
|
||||
void ShowDiscreatePoint(visualization_msgs::Marker *points, std::vector<Eigen::Vector3d, Eigen::aligned_allocator<Eigen::Vector3d> > discreate_point);
|
||||
void ShowDiscreatePoint(robot_visualization_msgs::Marker *points, EigenTrajectoryPoint::Vector discreate_point);
|
||||
void ShowDiscreatePoint(robot_visualization_msgs::Marker *points, std::vector<Eigen::Vector3d, Eigen::aligned_allocator<Eigen::Vector3d> > discreate_point);
|
||||
|
||||
//TODO: move relate visualize function to new vislization.h
|
||||
int print();
|
||||
visualization_msgs::Marker ShowDiscreatePoint(EigenTrajectoryPoint::Vector& discreate_point, const std::string& frame_id, const std::string& name, double scale);
|
||||
visualization_msgs::Marker ShowDiscreatePoint2(EigenTrajectoryPoint::Vector& discreate_point, const std::string& frame_id, std_msgs::ColorRGBA point_color, const std::string& name, double scale);
|
||||
visualization_msgs::Marker ShowDiscreatePoint(std::vector<Eigen::Vector3d, Eigen::aligned_allocator<Eigen::Vector3d> > discreate_point, const std::string& frame_id, const std::string& name, double scale);
|
||||
visualization_msgs::Marker ShowDiscreatePoint2(std::vector<Eigen::Vector3d, Eigen::aligned_allocator<Eigen::Vector3d> > discreate_point, const std::string& frame_id, std_msgs::ColorRGBA point_color, const std::string& name, double scale);
|
||||
robot_visualization_msgs::Marker ShowDiscreatePoint(EigenTrajectoryPoint::Vector& discreate_point, const std::string& frame_id, const std::string& name, double scale);
|
||||
robot_visualization_msgs::Marker ShowDiscreatePoint2(EigenTrajectoryPoint::Vector& discreate_point, const std::string& frame_id, robot_std_msgs::ColorRGBA point_color, const std::string& name, double scale);
|
||||
robot_visualization_msgs::Marker ShowDiscreatePoint(std::vector<Eigen::Vector3d, Eigen::aligned_allocator<Eigen::Vector3d> > discreate_point, const std::string& frame_id, const std::string& name, double scale);
|
||||
robot_visualization_msgs::Marker ShowDiscreatePoint2(std::vector<Eigen::Vector3d, Eigen::aligned_allocator<Eigen::Vector3d> > discreate_point, const std::string& frame_id, robot_std_msgs::ColorRGBA point_color, const std::string& name, double scale);
|
||||
private:
|
||||
|
||||
|
||||
|
||||
@@ -1,14 +1,14 @@
|
||||
#ifndef CUSTOM_PLANNER_COLOR_H_
|
||||
#define CUSTOM_PLANNER_COLOR_H_
|
||||
|
||||
#include <std_msgs/ColorRGBA.h>
|
||||
#include <robot_std_msgs/ColorRGBA.h>
|
||||
|
||||
namespace agv_visualization
|
||||
{
|
||||
class Color : public std_msgs::ColorRGBA
|
||||
class Color : public robot_std_msgs::ColorRGBA
|
||||
{
|
||||
public:
|
||||
Color() : std_msgs::ColorRGBA() {}
|
||||
Color() : robot_std_msgs::ColorRGBA() {}
|
||||
Color(double red, double green, double blue) : Color(red, green, blue, 1.0) {}
|
||||
Color(double red, double green, double blue, double alpha) : Color() {
|
||||
r = red;
|
||||
|
||||
@@ -10,7 +10,7 @@ using namespace std;
|
||||
|
||||
// ROS
|
||||
#include <robot_geometry_msgs/PoseStamped.h>
|
||||
#include <visualization_msgs/Marker.h>
|
||||
#include <robot_visualization_msgs/Marker.h>
|
||||
|
||||
// Costmap used for the map representation
|
||||
#include <costmap_2d/costmap_2d_robot.h>
|
||||
|
||||
Reference in New Issue
Block a user