Exploration template. More...
#include <exploration.hpp>
Public Member Functions | |
void | control (const Target &target, const std::string &map_frame_id, const std::string &base_frame_id, double frequency, double val_dt, double val_horizon) |
Executes the exploration stack. More... | |
Exploration (ros::NodeHandle &nh, const ErgodicControl< ModelT > &ergodic_control, const Collision &collision, const DynamicWindow &dwa) | |
Constructor. More... | |
void | init () |
Initialize subscribers and publishers. More... | |
void | mapCallback (const nav_msgs::OccupancyGrid::ConstPtr &msg) |
Occupancy grid callback. More... | |
void | odomCallback (const nav_msgs::Odometry &msg) |
Odometry callback. More... | |
Exploration template.
Definition at line 66 of file exploration.hpp.
ergodic_exploration::Exploration< ModelT >::Exploration | ( | ros::NodeHandle & | nh, |
const ErgodicControl< ModelT > & | ergodic_control, | ||
const Collision & | collision, | ||
const DynamicWindow & | dwa | ||
) |
Constructor.
nh | - NodeHandle |
ergodic_control | - ergodic controller |
collision | - collision detector |
dwa | - dynamic window local planner |
Definition at line 134 of file exploration.hpp.
void ergodic_exploration::Exploration< ModelT >::control | ( | const Target & | target, |
const std::string & | map_frame_id, | ||
const std::string & | base_frame_id, | ||
double | frequency, | ||
double | val_dt, | ||
double | val_horizon | ||
) |
Executes the exploration stack.
target | - target distribution |
map_frame_id | - map frame |
base_frame_id | - robot's base link frame |
frequency | - control loop frequency |
dt | - time step in integration |
horizon | - length of integration |
publishes a body twist at a fixed frequency
Definition at line 177 of file exploration.hpp.
void ergodic_exploration::Exploration< ModelT >::init |
Initialize subscribers and publishers.
Definition at line 149 of file exploration.hpp.
void ergodic_exploration::Exploration< ModelT >::mapCallback | ( | const nav_msgs::OccupancyGrid::ConstPtr & | msg | ) |
Occupancy grid callback.
msg | - occupancy grid message |
Definition at line 169 of file exploration.hpp.
void ergodic_exploration::Exploration< ModelT >::odomCallback | ( | const nav_msgs::Odometry & | msg | ) |
Odometry callback.
msg | - odometry message |
updates the robot's twist in the body frame [vx, vy, w]
Definition at line 161 of file exploration.hpp.
|
private |
Definition at line 127 of file exploration.hpp.
|
private |
Definition at line 113 of file exploration.hpp.
|
private |
Definition at line 114 of file exploration.hpp.
|
private |
Definition at line 129 of file exploration.hpp.
|
private |
Definition at line 112 of file exploration.hpp.
|
private |
Definition at line 119 of file exploration.hpp.
|
private |
Definition at line 116 of file exploration.hpp.
|
private |
Definition at line 124 of file exploration.hpp.
|
private |
Definition at line 110 of file exploration.hpp.
|
private |
Definition at line 125 of file exploration.hpp.
|
private |
Definition at line 128 of file exploration.hpp.
|
private |
Definition at line 130 of file exploration.hpp.
|
private |
Definition at line 121 of file exploration.hpp.
|
private |
Definition at line 122 of file exploration.hpp.
|
private |
Definition at line 118 of file exploration.hpp.