main.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2020-2023 RaccoonLab.
3  *
4  * This program is free software: you can redistribute it and/or modify
5  * it under the terms of the GNU General Public License as published by
6  * the Free Software Foundation, version 3.
7  *
8  * This program is distributed in the hope that it will be useful, but
9  * WITHOUT ANY WARRANTY; without even the implied warranty of
10  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
11  * General Public License for more details.
12  *
13  * You should have received a copy of the GNU General Public License
14  * along with this program. If not, see <http://www.gnu.org/licenses/>.
15  *
16  * Authors: Dmitry Ponomarev <ponomarevda96@gmail.com>
17  * Roman Fedorenko <frontwise@gmail.com>
18  */
19 
20 #include "main.hpp"
21 #include <rosgraph_msgs/Clock.h>
22 #include <geometry_msgs/TransformStamped.h>
23 #include <std_msgs/Time.h>
24 
25 #include "quadcopter.hpp"
26 #include "octocopter.hpp"
27 #include "vtolDynamicsSim.hpp"
28 #include "cs_converter.hpp"
29 
30 
31 int main(int argc, char **argv){
32  ros::init(argc, argv, "uav_dynamics_node");
35  }
36 
37  ros::NodeHandle node_handler("inno_dynamics_sim");
38  Uav_Dynamics uav_dynamics_node(node_handler);
39  if(uav_dynamics_node.init() == -1){
40  ROS_ERROR("Shutdown.");
41  ros::shutdown();
42  return -1;
43  }
44 
45  ros::spin();
46  return 0;
47 }
48 
49 
51  _node(nh),
52  _sensors(&nh),
53  _rviz_visualizator(_node),
54  _scenarioManager(_node, _actuators, _sensors),
55  _logger(_actuators, _sensors, info){
56 }
57 
58 
63  if(getParamsFromRos() == -1){
64  return -1;
65  }else if(initDynamicsSimulator() == -1){
66  return -1;
67  }else if(initSensors() == -1){
68  return -1;
69  }else if(initCalibration() == -1){
70  return -1;
71  }else if(_rviz_visualizator.init(uavDynamicsSim_) == -1){
72  return -1;
73  }else if(startClockAndThreads() == -1){
74  return -1;
75  }
76 
77  return 0;
78 }
79 
81  const std::string SIM_PARAMS_PATH = "/uav/sim_params/";
82  if(!ros::param::get(SIM_PARAMS_PATH + "use_sim_time", useSimTime_ ) ||
83  !_node.getParam("logging_type", info.loggingTypeName) ||
84  !_node.getParam("dynamics", info.dynamicsName) ||
85  !ros::param::get(SIM_PARAMS_PATH + "wind_ned", _wind_ned) ||
86  !ros::param::get(SIM_PARAMS_PATH + "init_pose", initPose_)){
87  ROS_ERROR("Dynamics: There is no at least one of required simulator parameters.");
88  return -1;
89  }
90  return 0;
91 }
92 
94  if(info.dynamicsName == "quadcopter"){
96  uavDynamicsSim_ = std::make_shared<QuadcopterDynamics>();
98  }else if(info.dynamicsName == "octorotor"){
100  uavDynamicsSim_ = std::make_shared<OctocopterDynamics>();
102  }else if(info.dynamicsName == "vtol_dynamics"){
103  uavDynamicsSim_ = std::make_shared<VtolDynamics>();
106  }else{
107  ROS_ERROR("Dynamics type with name \"%s\" is not exist.", info.dynamicsName.c_str());
108  return -1;
109  }
110 
111  if(info.loggingTypeName == "standard_vtol"){
113  }else if(info.loggingTypeName == "vtol_8_motors_logger"){
115  }else if(info.loggingTypeName == "quadcopter"){
117  }else{
118  ROS_ERROR("Wrong logging type. It should be either 'standard_vtol' or 'quadcopter'");
119  return -1;
120  }
121 
122  if(uavDynamicsSim_ == nullptr || uavDynamicsSim_->init() == -1){
123  ROS_ERROR("Can't init uav dynamics sim. Shutdown.");
124  return -1;
125  }
126 
127  Eigen::Vector3d initPosition(initPose_.at(0), initPose_.at(1), initPose_.at(2));
128  Eigen::Quaterniond initAttitudeWXYZ(initPose_.at(6), initPose_.at(3), initPose_.at(4), initPose_.at(5));
129  initAttitudeWXYZ.normalize();
130  uavDynamicsSim_->setInitialPosition(initPosition, initAttitudeWXYZ);
131  Eigen::Vector3d wind_ned(_wind_ned[0], _wind_ned[1], _wind_ned[2]);
132  uavDynamicsSim_->setWindParameter(wind_ned, 0.0);
133  return 0;
134 }
135 
140  return _sensors.init(uavDynamicsSim_);
141 }
142 
144  calibrationSub_ = _node.subscribe("/uav/calibration", 1, &Uav_Dynamics::calibrationCallback, this);
145  return 0;
146 }
147 
149  ros::Duration(0.1).sleep();
150  if(useSimTime_){
151  clockPub_ = _node.advertise<rosgraph_msgs::Clock>("/clock", 1);
152  rosgraph_msgs::Clock clock_time;
153  clock_time.clock = currentTime_;
154  clockPub_.publish(clock_time);
155  }else{
156  // Get the current time if we are using wall time. Otherwise, use 0 as initial clock.
158  }
159 
160 
163  this);
165 
167  proceedDynamicsTask.detach();
168 
170  publishToRosTask.detach();
171 
172  diagnosticTask = std::thread(&Uav_Dynamics::performLogging, this, 1.0);
173  diagnosticTask.detach();
174 
175  return 0;
176 }
177 
183  if (useSimTime_){
185  rosgraph_msgs::Clock clock_time;
186  clock_time.clock = currentTime_;
187  clockPub_.publish(clock_time);
188  } else {
189  ros::Time loopStartTime = ros::Time::now();
190  dt_secs_ = (loopStartTime - currentTime_).toSec();
191  currentTime_ = loopStartTime;
192  }
193 }
194 
195 void Uav_Dynamics::performLogging(double periodSec){
196  while(ros::ok()){
197  auto crnt_time = std::chrono::system_clock::now();
198  auto sleed_period = std::chrono::seconds(int(periodSec * clockScale_));
199 
200  std::stringstream logStream;
201  auto pose = uavDynamicsSim_->getVehiclePosition();
202  _logger.createStringStream(logStream, pose, dynamicsCounter_, rosPubCounter_, periodSec);
203  dynamicsCounter_ = 0;
204  rosPubCounter_ = 0;
205 
206 
207  ROS_INFO_STREAM(logStream.str());
208  fflush(stdout);
209  std::this_thread::sleep_until(crnt_time + sleed_period);
210  }
211 }
212 
213 // The sequence of steps for lockstep are:
214 // The simulation sends a sensor message HIL_SENSOR including a timestamp time_usec to update
215 // the sensor state and time of PX4.
216 // PX4 receives this and does one iteration of state estimation, controls, etc. and eventually
217 // sends an actuator message HIL_ACTUATOR_CONTROLS.
218 // The simulation waits until it receives the actuator/motor message, then simulates the physics
219 // and calculates the next sensor message to send to PX4 again.
220 // The system starts with a "freewheeling" period where the simulation sends sensor messages
221 // including time and therefore runs PX4 until it has initialized and responds with an actautor
222 // message.
223 // But instead of waiting actuators cmd, we will wait for an arming
224 void Uav_Dynamics::proceedDynamics(double periodSec){
225  while(ros::ok()){
226  auto crnt_time = std::chrono::system_clock::now();
227  auto sleed_period = std::chrono::milliseconds(int(1000 * periodSec * clockScale_));
228  auto time_point = crnt_time + sleed_period;
230 
232  uavDynamicsSim_->calibrate(calibrationType_);
234  static auto crnt_time = std::chrono::system_clock::now();
235  auto prev_time = crnt_time;
236  crnt_time = std::chrono::system_clock::now();
237  auto time_dif_sec = static_cast<double>((crnt_time - prev_time).count()) * 1e-9;
238 
240  const double MAX_TIME_DIFF_SEC = 10 * periodSec;
241  if (time_dif_sec > MAX_TIME_DIFF_SEC) {
242  ROS_ERROR_STREAM_THROTTLE(1, "Time jumping: " << time_dif_sec << " seconds.");
243  time_dif_sec = MAX_TIME_DIFF_SEC;
244  }
245 
246  uavDynamicsSim_->process(time_dif_sec, _actuators.actuators);
247  }else{
248  uavDynamicsSim_->land();
249  }
250 
252 
253  std::this_thread::sleep_until(time_point);
254  }
255 }
256 
257 void Uav_Dynamics::publishToRos(double period){
258  while(ros::ok()){
259  auto crnt_time = std::chrono::system_clock::now();
260  auto sleed_period = std::chrono::microseconds(int(1000000 * period * clockScale_));
261  auto time_point = crnt_time + sleed_period;
262  rosPubCounter_++;
263 
265 
266  static auto next_time = std::chrono::system_clock::now();
267  if(crnt_time > next_time){
270  }
271  next_time += std::chrono::milliseconds(int(50));
272  }
273 
274  std::this_thread::sleep_until(time_point);
275  }
276 }
277 
278 void Uav_Dynamics::calibrationCallback(std_msgs::UInt8 msg){
279  if(calibrationType_ != static_cast<UavDynamicsSimBase::SimMode_t>(msg.data)){
280  ROS_INFO_STREAM_THROTTLE(1, "calibration type: " << msg.data + 0);
281  }
282  calibrationType_ = static_cast<UavDynamicsSimBase::SimMode_t>(msg.data);
283 }
UavDynamicsSimBase::SimMode_t
SimMode_t
Definition: uavDynamicsSimBase.hpp:57
Uav_Dynamics::_scenarioManager
ScenarioManager _scenarioManager
Definition: main.hpp:73
Actuators::getArmingStatus
ArmingStatus getArmingStatus()
Definition: actuators.cpp:34
ROS_ERROR_STREAM_THROTTLE
#define ROS_ERROR_STREAM_THROTTLE(period, args)
Uav_Dynamics::rosPubCounter_
uint64_t rosPubCounter_
Definition: main.hpp:83
quadcopter.hpp
Uav_Dynamics::initCalibration
int8_t initCalibration()
Definition: main.cpp:143
Uav_Dynamics::publishToRosTask
std::thread publishToRosTask
Definition: main.hpp:88
Uav_Dynamics::getParamsFromRos
int8_t getParamsFromRos()
Definition: main.cpp:80
ArmingStatus::DISARMED
@ DISARMED
Uav_Dynamics::Uav_Dynamics
Uav_Dynamics(ros::NodeHandle nh)
Definition: main.cpp:50
Uav_Dynamics::useSimTime_
bool useSimTime_
Definition: main.hpp:63
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ScenarioManager::init
void init()
Definition: scenarios.cpp:21
ros::param::get
ROSCPP_DECL bool get(const std::string &key, bool &b)
Uav_Dynamics::publishToRos
void publishToRos(double period)
Definition: main.cpp:257
Uav_Dynamics::currentTime_
ros::Time currentTime_
Definition: main.hpp:60
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
DynamicsType::QUADCOPTER
@ QUADCOPTER
Uav_Dynamics::diagnosticTask
std::thread diagnosticTask
Definition: main.hpp:89
Uav_Dynamics::proceedDynamics
void proceedDynamics(double period)
Definition: main.cpp:224
Sensors::publishStateToCommunicator
void publishStateToCommunicator(uint8_t dynamicsNotation)
Definition: sensors.cpp:95
Uav_Dynamics::initPose_
std::vector< double > initPose_
Definition: main.hpp:65
main
int main(int argc, char **argv)
Definition: main.cpp:31
ros::shutdown
ROSCPP_DECL void shutdown()
Uav_Dynamics::ROS_PUB_PERIOD_SEC
const float ROS_PUB_PERIOD_SEC
Definition: main.hpp:96
DynamicsInfo::loggingType
LoggingType loggingType
Definition: dynamics.hpp:43
UavDynamicsSimBase::SimMode_t::NORMAL
@ NORMAL
ros::console::set_logger_level
ROSCONSOLE_DECL bool set_logger_level(const std::string &name, levels::Level level)
DynamicsInfo::notation
DynamicsNotation_t notation
Definition: dynamics.hpp:46
RvizVisualizator::publish
void publish(uint8_t dynamicsNotation)
Definition: rviz_visualization.cpp:69
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
main.hpp
ros::ok
ROSCPP_DECL bool ok()
StateLogger::createStringStream
void createStringStream(std::stringstream &logStream, const Eigen::Vector3d &pose, double dynamicsCounter, double rosPubCounter, double periodSec)
Definition: logger.cpp:39
Uav_Dynamics::startClockAndThreads
int8_t startClockAndThreads()
Definition: main.cpp:148
ros::WallTimer::start
void start()
Uav_Dynamics::uavDynamicsSim_
std::shared_ptr< UavDynamicsSimBase > uavDynamicsSim_
Definition: main.hpp:57
StateLogger::init
void init(double clockScale, double dt_secs)
Definition: logger.cpp:34
DynamicsNotation_t::PX4_NED_FRD
@ PX4_NED_FRD
vtolDynamicsSim.hpp
Uav_Dynamics::info
DynamicsInfo info
Definition: main.hpp:68
Actuators::init
void init(ros::NodeHandle &node)
Definition: actuators.cpp:21
Uav_Dynamics::clockScale_
double clockScale_
Definition: main.hpp:62
Uav_Dynamics::dynamicsCounter_
uint64_t dynamicsCounter_
Definition: main.hpp:82
Uav_Dynamics::clockPub_
ros::Publisher clockPub_
Definition: main.hpp:58
DynamicsType::OCTOCOPTER
@ OCTOCOPTER
ROS_INFO_STREAM_THROTTLE
#define ROS_INFO_STREAM_THROTTLE(period, args)
Uav_Dynamics::initSensors
int8_t initSensors()
Definition: main.cpp:136
Uav_Dynamics::_logger
StateLogger _logger
Definition: main.hpp:74
Uav_Dynamics::simulationLoopTimerCallback
void simulationLoopTimerCallback(const ros::WallTimerEvent &event)
Main Simulator loop.
Definition: main.cpp:182
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
Uav_Dynamics
UAV Dynamics class used for dynamics, IMU, and angular rate control simulation node.
Definition: main.hpp:43
ros::console::levels::Info
Info
Actuators::actuators
std::vector< double > actuators
Definition: actuators.hpp:39
DynamicsInfo::dynamicsType
DynamicsType dynamicsType
Definition: dynamics.hpp:41
octocopter.hpp
Uav_Dynamics::calibrationType_
UavDynamicsSimBase::SimMode_t calibrationType_
Definition: main.hpp:78
RvizVisualizator::init
int8_t init(const std::shared_ptr< UavDynamicsSimBase > &uavDynamicsSim_)
Definition: rviz_visualization.cpp:34
DynamicsType::VTOL
@ VTOL
LoggingType::STANDARD_VTOL
@ STANDARD_VTOL
ros::WallTimerEvent
ros::console::notifyLoggerLevelsChanged
ROSCONSOLE_DECL void notifyLoggerLevelsChanged()
ros::Time
Uav_Dynamics::_actuators
Actuators _actuators
Definition: main.hpp:70
Uav_Dynamics::_wind_ned
std::vector< double > _wind_ned
Definition: main.hpp:66
Uav_Dynamics::_sensors
Sensors _sensors
Definition: main.hpp:71
Uav_Dynamics::simulationLoopTimer_
ros::WallTimer simulationLoopTimer_
Definition: main.hpp:86
DynamicsInfo::loggingTypeName
std::string loggingTypeName
Definition: dynamics.hpp:44
Uav_Dynamics::calibrationCallback
void calibrationCallback(std_msgs::UInt8 msg)
Definition: main.cpp:278
Uav_Dynamics::_node
ros::NodeHandle _node
Definition: main.hpp:56
ROS_ERROR
#define ROS_ERROR(...)
LoggingType::VTOL_8_MOTORS
@ VTOL_8_MOTORS
Uav_Dynamics::dt_secs_
double dt_secs_
Definition: main.hpp:61
ros::spin
ROSCPP_DECL void spin()
ros::Duration::sleep
bool sleep() const
DynamicsNotation_t::ROS_ENU_FLU
@ ROS_ENU_FLU
Uav_Dynamics::init
int8_t init()
Definition: main.cpp:62
ROSCONSOLE_DEFAULT_NAME
#define ROSCONSOLE_DEFAULT_NAME
ros::WallDuration
Uav_Dynamics::_rviz_visualizator
RvizVisualizator _rviz_visualizator
Definition: main.hpp:72
DynamicsInfo::dynamicsName
std::string dynamicsName
Definition: dynamics.hpp:40
Uav_Dynamics::proceedDynamicsTask
std::thread proceedDynamicsTask
Definition: main.hpp:87
ros::Duration
ros::NodeHandle::createWallTimer
WallTimer createWallTimer(WallDuration period, const WallTimerCallback &callback, bool oneshot=false, bool autostart=true) const
Uav_Dynamics::performLogging
void performLogging(double period)
Definition: main.cpp:195
ros::NodeHandle
Uav_Dynamics::calibrationSub_
ros::Subscriber calibrationSub_
Definition: main.hpp:77
cs_converter.hpp
Uav_Dynamics::initDynamicsSimulator
int8_t initDynamicsSimulator()
Definition: main.cpp:93
LoggingType::QUADCOPTER
@ QUADCOPTER
Sensors::init
int8_t init(const std::shared_ptr< UavDynamicsSimBase > &uavDynamicsSim)
Definition: sensors.cpp:42
RvizVisualizator::publishTf
void publishTf(uint8_t dynamicsNotation)
Perform TF transform between GLOBAL_FRAME -> UAV_FRAME in ROS (enu/flu) format.
Definition: rviz_visualization.cpp:158
ros::Time::now
static Time now()


inno_vtol_dynamics
Author(s): Roman Fedorenko, Dmitry Ponomarev, Ezra Tal, Winter Guerra
autogenerated on Mon Dec 9 2024 03:13:35