Go to the documentation of this file.
21 #include <rosgraph_msgs/Clock.h>
22 #include <geometry_msgs/TransformStamped.h>
23 #include <std_msgs/Time.h>
31 int main(
int argc,
char **argv){
32 ros::init(argc, argv,
"uav_dynamics_node");
39 if(uav_dynamics_node.
init() == -1){
53 _rviz_visualizator(_node),
54 _scenarioManager(_node, _actuators, _sensors),
55 _logger(_actuators, _sensors, info){
81 const std::string SIM_PARAMS_PATH =
"/uav/sim_params/";
87 ROS_ERROR(
"Dynamics: There is no at least one of required simulator parameters.");
118 ROS_ERROR(
"Wrong logging type. It should be either 'standard_vtol' or 'quadcopter'");
123 ROS_ERROR(
"Can't init uav dynamics sim. Shutdown.");
129 initAttitudeWXYZ.normalize();
152 rosgraph_msgs::Clock clock_time;
185 rosgraph_msgs::Clock clock_time;
197 auto crnt_time = std::chrono::system_clock::now();
198 auto sleed_period = std::chrono::seconds(
int(periodSec *
clockScale_));
200 std::stringstream logStream;
209 std::this_thread::sleep_until(crnt_time + sleed_period);
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;
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;
240 const double MAX_TIME_DIFF_SEC = 10 * periodSec;
241 if (time_dif_sec > MAX_TIME_DIFF_SEC) {
243 time_dif_sec = MAX_TIME_DIFF_SEC;
253 std::this_thread::sleep_until(time_point);
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;
266 static auto next_time = std::chrono::system_clock::now();
267 if(crnt_time > next_time){
271 next_time += std::chrono::milliseconds(
int(50));
274 std::this_thread::sleep_until(time_point);
ScenarioManager _scenarioManager
ArmingStatus getArmingStatus()
#define ROS_ERROR_STREAM_THROTTLE(period, args)
std::thread publishToRosTask
int8_t getParamsFromRos()
Uav_Dynamics(ros::NodeHandle nh)
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ROSCPP_DECL bool get(const std::string &key, bool &b)
void publishToRos(double period)
bool getParam(const std::string &key, bool &b) const
std::thread diagnosticTask
void proceedDynamics(double period)
void publishStateToCommunicator(uint8_t dynamicsNotation)
std::vector< double > initPose_
int main(int argc, char **argv)
ROSCPP_DECL void shutdown()
const float ROS_PUB_PERIOD_SEC
ROSCONSOLE_DECL bool set_logger_level(const std::string &name, levels::Level level)
DynamicsNotation_t notation
void publish(uint8_t dynamicsNotation)
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
void createStringStream(std::stringstream &logStream, const Eigen::Vector3d &pose, double dynamicsCounter, double rosPubCounter, double periodSec)
int8_t startClockAndThreads()
std::shared_ptr< UavDynamicsSimBase > uavDynamicsSim_
void init(double clockScale, double dt_secs)
void init(ros::NodeHandle &node)
uint64_t dynamicsCounter_
#define ROS_INFO_STREAM_THROTTLE(period, args)
void simulationLoopTimerCallback(const ros::WallTimerEvent &event)
Main Simulator loop.
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())
#define ROS_INFO_STREAM(args)
UAV Dynamics class used for dynamics, IMU, and angular rate control simulation node.
std::vector< double > actuators
DynamicsType dynamicsType
UavDynamicsSimBase::SimMode_t calibrationType_
int8_t init(const std::shared_ptr< UavDynamicsSimBase > &uavDynamicsSim_)
ROSCONSOLE_DECL void notifyLoggerLevelsChanged()
std::vector< double > _wind_ned
ros::WallTimer simulationLoopTimer_
std::string loggingTypeName
void calibrationCallback(std_msgs::UInt8 msg)
#define ROSCONSOLE_DEFAULT_NAME
RvizVisualizator _rviz_visualizator
std::thread proceedDynamicsTask
WallTimer createWallTimer(WallDuration period, const WallTimerCallback &callback, bool oneshot=false, bool autostart=true) const
void performLogging(double period)
ros::Subscriber calibrationSub_
int8_t initDynamicsSimulator()
int8_t init(const std::shared_ptr< UavDynamicsSimBase > &uavDynamicsSim)
void publishTf(uint8_t dynamicsNotation)
Perform TF transform between GLOBAL_FRAME -> UAV_FRAME in ROS (enu/flu) format.
inno_vtol_dynamics
Author(s): Roman Fedorenko, Dmitry Ponomarev, Ezra Tal, Winter Guerra
autogenerated on Mon Dec 9 2024 03:13:35