-
Notifications
You must be signed in to change notification settings - Fork 121
Interface
Fadri Furrer edited this page Jan 19, 2016
·
2 revisions
The planner is called via a service. To embed the planner in your own c++ project add the following snipplet:
#include <ros/ros.h>
#include <nbvplanner/nbvp_srv.h>
...
int iteration = 0;
while (ros::ok()) {
nbvplanner::nbvp_srv planSrv;
planSrv.request.header.stamp = ros::Time::now();
planSrv.request.header.seq = iteration;
planSrv.request.header.frame_id = ros::this_node::getNamespace();
if (ros::service::call("nbvplanner", planSrv)) {
...
// Process the computed path in planSrv.response.path to make
// the robot track it
...
iteration++;
}
} else {
ROS_WARN_THROTTLE(1, "Planner not reachable");
ros::Duration(1.0).sleep();
}
}
-
disparity
(stereo_msgs/DisparityImage) - disparity image to subscribe to. -
pointcloud
(sensor_msgs/PointCloud2) - pointcloud to subscribe to. -
pointcloud_throttled
(sensor_msgs/PointCloud2) - pointcloud to subscribe to, throtteling with time constant defined by the parameter pcl_throttle. -
cam0/camera_info
(sensor_msgs/CameraInfo) - left camera info. -
cam1/camera_info
(sensor_msgs/CameraInfo) - right camera info. -
pose
(geometry_msgs/PoseStamped) - vehicle pose. -
peer_pose_1
(geometry_msgs/PoseStamped) - vehicle pose of peer agent 1 (if applicable). -
peer_pose_2
(geometry_msgs/PoseStamped) - vehicle pose of peer agent 2 (if applicable). -
peer_pose_3
(geometry_msgs/PoseStamped) - vehicle pose of peer agent 3 (if applicable). -
/evasionSegment
(multiagent_collision_check::Segment) - path segments of peer agents for collision avoidance (never needs remaping).
-
octomap_occupied
(visualization_msgs/MarkerArray) - marker array showing occupied octomap cells, colored by z. -
octomap_free
(visualization_msgs/MarkerArray) - marker array showing free octomap cells, colored by z. -
octomap_full
(octomap_msgs/Octomap) - octomap with full probabilities. -
octomap_binary
(octomap_msgs/Octomap) - octomap with binary occupancy - free or occupied, taken by max likelihood of each node. -
inspectionPath
(visualization_msgs/Marker) - visualization markers for display in rviz.
-
reset_map
(std_srvs/Empty) - clear the map. -
publish_all
(std_srvs/Empty) - publish all the topics in the above section. -
get_map
(octomap_msgs/GetOctomap) - returns binary octomap message. -
save_map
(volumetric_msgs/SaveMap) - save map to the specifiedfile_path
. -
load_map
(volumetric_msgs/LoadMap) - load map from the specifiedfile_path
. -
nbvplanner
(nbvplanner/nbvp_srv) - plan the next step.
Contact details: Andreas Bircher, Kostas Alexis, Autonomous Systems Lab