Go to the documentation of this file.
29 #include <std_msgs/UInt8.h>
99 #endif // SRC_MAIN_HPP
ScenarioManager _scenarioManager
std::thread publishToRosTask
int8_t getParamsFromRos()
Uav_Dynamics(ros::NodeHandle nh)
void publishToRos(double period)
std::thread diagnosticTask
void proceedDynamics(double period)
std::vector< double > initPose_
const float ROS_PUB_PERIOD_SEC
int8_t startClockAndThreads()
std::shared_ptr< UavDynamicsSimBase > uavDynamicsSim_
uint64_t dynamicsCounter_
void simulationLoopTimerCallback(const ros::WallTimerEvent &event)
Main Simulator loop.
UAV Dynamics class used for dynamics, IMU, and angular rate control simulation node.
UavDynamicsSimBase::SimMode_t calibrationType_
std::vector< double > _wind_ned
ros::WallTimer simulationLoopTimer_
void calibrationCallback(std_msgs::UInt8 msg)
RvizVisualizator _rviz_visualizator
std::thread proceedDynamicsTask
void performLogging(double period)
ros::Subscriber calibrationSub_
int8_t initDynamicsSimulator()
inno_vtol_dynamics
Author(s): Roman Fedorenko, Dmitry Ponomarev, Ezra Tal, Winter Guerra
autogenerated on Mon Dec 9 2024 03:13:35