PX4 simulation stack
|
Node for simple demo of point cloud construction. More...
#include <cmath>
#include <string>
#include <cstdlib>
#include <ros/ros.h>
#include <ros/topic.h>
#include <laser_assembler/AssembleScans2.h>
#include <geometry_msgs/PoseStamped.h>
#include <geometry_msgs/TwistStamped.h>
#include <sensor_msgs/NavSatFix.h>
#include <sensor_msgs/PointCloud2.h>
#include <mavros_msgs/CommandBool.h>
#include <mavros_msgs/SetMode.h>
#include <mavros_msgs/State.h>
#include <mavros_msgs/CommandTOL.h>
#include <mavros_msgs/CommandHome.h>
#include <pcl/io/pcd_io.h>
#include <pcl/point_types.h>
#include <pcl_conversions/pcl_conversions.h>
Go to the source code of this file.
Functions | |
bool | isGoalReached (const geometry_msgs::PoseStamped &curr_pose, const geometry_msgs::PoseStamped &goal_pose, double threshold=0.5) |
std::array< std::vector< double >, 2 > | linearInterp (const std::array< double, 2 > &p1, const std::array< double, 2 > &p2, const double step) |
Perform linear interpolation. More... | |
std::vector< geometry_msgs::PoseStamped > | getBilinearPath (const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, const double step=0.05) |
Return interpolated path using bilinear interpolation from two waypoints. More... | |
int | main (int argc, char **argv) |
Node for simple demo of point cloud construction.
Definition in file simple_sweep_demo.cpp.
std::vector<geometry_msgs::PoseStamped> getBilinearPath | ( | const geometry_msgs::PoseStamped & | start, |
const geometry_msgs::PoseStamped & | goal, | ||
const double | step = 0.05 |
||
) |
Return interpolated path using bilinear interpolation from two waypoints.
start | Start waypoint |
goal | Goal waypoint |
step | Step size of interpolation |
Definition at line 105 of file simple_sweep_demo.cpp.
bool isGoalReached | ( | const geometry_msgs::PoseStamped & | curr_pose, |
const geometry_msgs::PoseStamped & | goal_pose, | ||
double | threshold = 0.5 |
||
) |
Definition at line 40 of file simple_sweep_demo.cpp.
std::array<std::vector<double>, 2> linearInterp | ( | const std::array< double, 2 > & | p1, |
const std::array< double, 2 > & | p2, | ||
const double | step | ||
) |
Perform linear interpolation.
p1 | First point |
p2 | Second point |
step | Step size of interpolation |
Definition at line 57 of file simple_sweep_demo.cpp.
int main | ( | int | argc, |
char ** | argv | ||
) |
Definition at line 147 of file simple_sweep_demo.cpp.