exploration_omni_node.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * BSD 3-Clause License
3  *
4  * Copyright (c) 2020 Northwestern University
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions are met:
9  *
10  * * Redistributions of source code must retain the above copyright notice, this
11  * list of conditions and the following disclaimer.
12  *
13  * * Redistributions in binary form must reproduce the above copyright notice,
14  * this list of conditions and the following disclaimer in the documentation
15  * and/or other materials provided with the distribution.
16  *
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived from
19  * this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
24  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
25  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
26  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
27  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
29  * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
30  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
31  *********************************************************************/
87 
88 using arma::mat;
89 using arma::vec;
90 
98 
99 constexpr char LOGNAME[] = "omni exploration";
100 
101 int main(int argc, char** argv)
102 {
103  ROS_INFO_STREAM_NAMED(LOGNAME, "Starting exploration");
104  ros::init(argc, argv, "exploration");
105  ros::NodeHandle nh;
106  ros::NodeHandle pnh("~");
107 
109  spinner.start();
110 
111  arma::arma_rng::set_seed_random();
112 
113  // TODO: Add noise to motion model
114  // motion model
115  const Omni omni;
116 
118  const auto map_frame_id = pnh.param<std::string>("map_frame_id", "map");
119  const auto base_frame_id = pnh.param<std::string>("base_frame_id", "base_link");
120 
121  // publish on cmd_vel at a constant frequency
122  const double frequency = pnh.param("frequency", 10.0);
123  // EC validation
124  const double val_dt = pnh.param("val_dt", 0.1);
125  const double val_horizon = pnh.param("val_horizon", 0.5);
126 
127  const double max_vel_x = pnh.param("max_vel_x", 1.0);
128  const double max_vel_y = pnh.param("max_vel_y", 1.0);
129  const double max_rot_vel = pnh.param("max_rot_vel", 1.0);
130 
131  const double min_vel_x = pnh.param("min_vel_x", -1.0);
132  const double min_vel_y = pnh.param("min_vel_y", -1.0);
133  const double min_rot_vel = pnh.param("min_rot_vel", -1.0);
134 
135  const double acc_lim_x = pnh.param("acc_lim_x", 1.0);
136  const double acc_lim_y = pnh.param("acc_lim_y", 1.0);
137  const double acc_lim_th = pnh.param("acc_lim_th", 1.0);
138 
139  const vec umin = { min_vel_x, min_vel_y, min_rot_vel };
140  const vec umax = { max_vel_x, max_vel_y, max_rot_vel };
141 
142  // collision
143  const double boundary_radius = pnh.param("boundary_radius", 0.7);
144  const double search_radius = pnh.param("search_radius", 1.0);
145  const double obstacle_threshold = pnh.param("obstacle_threshold", 0.2);
146  const double occupied_threshold = pnh.param("occupied_threshold", 0.8);
147 
148  // ergodic control
149  const double ec_dt = pnh.param("ec_dt", 0.1);
150  const double ec_horizon = pnh.param("ec_horizon", 2.0);
151  const double target_resolution = pnh.param("target_resolution", 0.1);
152  const double expl_weight = pnh.param("expl_weight", 1.0);
153  const unsigned int num_basis = pnh.param("num_basis", 10);
154  const unsigned int buffer_size = pnh.param("buffer_size", 1e6);
155  const unsigned int batch_size = pnh.param("batch_size", 100);
156 
157  std::vector<double> control_weights = { 1.0, 1.0, 1.0 };
158  pnh.getParam("control_weights", control_weights);
159 
160  // Inverse of diaganol is 1 over the diaganol
161  mat Rinv(3, 3, arma::fill::zeros);
162  Rinv(0, 0) = 1.0 / control_weights.at(0);
163  Rinv(1, 1) = 1.0 / control_weights.at(1);
164  Rinv(2, 2) = 1.0 / control_weights.at(2);
165 
166  // dwa
167  const double dwa_dt = pnh.param("dwa_dt", 0.1);
168  const double dwa_horizon = pnh.param("dwa_horizon", 1.0);
169  const double acc_dt = pnh.param("acc_dt", 0.2);
170  const unsigned int vx_samples = pnh.param("vx_samples", 3);
171  const unsigned int vy_samples = pnh.param("vy_samples", 8);
172  const unsigned int vth_samples = pnh.param("vth_samples", 5);
173 
174  if (dwa_horizon > ec_horizon)
175  {
177  LOGNAME, "Dynamic window horizon is greater than the ergodic control horizon");
178  ros::shutdown();
179  }
180 
181  // target
182  XmlRpc::XmlRpcValue means;
183  XmlRpc::XmlRpcValue sigmas;
184  pnh.getParam("means", means);
185  pnh.getParam("sigmas", sigmas);
186  const auto num_targets = static_cast<unsigned int>(means.size());
187 
188  GaussianList gaussians(num_targets);
189  for (unsigned int i = 0; i < num_targets; i++)
190  {
191  gaussians.at(i) = { { means[i][0], means[i][1] }, { sigmas[i][0], sigmas[i][1] } };
192  }
193 
194  const Target target(gaussians);
195 
197  const Collision collision(boundary_radius, search_radius, obstacle_threshold,
198  occupied_threshold);
199 
200  const ErgodicControl ergodic_control(omni, collision, ec_dt, ec_horizon,
201  target_resolution, expl_weight, num_basis,
202  buffer_size, batch_size, Rinv, umin, umax);
203 
204  const DynamicWindow dwa(collision, dwa_dt, dwa_horizon, acc_dt, acc_lim_x, acc_lim_y,
205  acc_lim_th, max_vel_x, min_vel_x, max_vel_y, min_vel_y,
206  max_rot_vel, min_rot_vel, vx_samples, vy_samples, vth_samples);
207 
208  ergodic_exploration::Exploration<Omni> exploration(nh, ergodic_control, collision, dwa);
209 
210  // start exploring
211  exploration.control(target, map_frame_id, base_frame_id, frequency, val_dt, val_horizon);
212 
214 
215  // ros::waitForShutdown();
216  ROS_INFO_STREAM_NAMED(LOGNAME, "Shutting down.");
217  return 0;
218 }
XmlRpc::XmlRpcValue::size
int size() const
ergodic_exploration::Exploration
Exploration template.
Definition: exploration.hpp:66
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros::AsyncSpinner
ros::shutdown
ROSCPP_DECL void shutdown()
ergodic_exploration::DynamicWindow
Dynamic window approach.
Definition: dynamic_window.hpp:52
spinner
void spinner()
main
int main(int argc, char **argv)
Definition: exploration_omni_node.cpp:101
exploration.hpp
Ergodic exploration with a user defined target and dynamic window approach for collision avoidance.
ergodic_exploration::Target
Target distribution.
Definition: target.hpp:110
ROS_ERROR_STREAM_NAMED
#define ROS_ERROR_STREAM_NAMED(name, args)
omni.hpp
Kinematic omni directional models control wheel velocities or body twist.
ergodic_exploration::Exploration::control
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.
Definition: exploration.hpp:177
LOGNAME
constexpr char LOGNAME[]
Definition: exploration_omni_node.cpp:99
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
ROS_INFO_STREAM_NAMED
#define ROS_INFO_STREAM_NAMED(name, args)
ergodic_exploration::GaussianList
std::vector< Gaussian > GaussianList
Definition: target.hpp:52
ergodic_exploration::ErgodicControl
Receding horizon ergodic trajectory optimization.
Definition: ergodic_control.hpp:73
ergodic_exploration::models::Omni
Kinematic model of omni directonal robot.
Definition: omni.hpp:164
XmlRpc::XmlRpcValue
ros::NodeHandle
ergodic_exploration::Collision
2D collision detection
Definition: collision.hpp:85


ergodic_exploration
Author(s): bostoncleek
autogenerated on Wed Mar 2 2022 00:17:13