Go to the documentation of this file.
20 #include <std_msgs/UInt8.h>
21 #include <mavros_msgs/ESCStatusItem.h>
25 static const constexpr
double PERIOD_1 = 1500.0;
26 static const constexpr
double PERIOD_2 = 1500.0;
27 static const constexpr
double PERIOD_3 = 2000.0;
31 std::string base_name = topic;
32 auto rpm_name = base_name +
"_rpm";
33 auto status_name = base_name +
"_status";
42 std_msgs::UInt8 state_msg;
46 mavros_msgs::ESCStatusItem rpm_msg;
47 rpm_msg.rpm =
static_cast<int32_t
>(rpm);
82 double timeSinceRestartMs = timeElapsedMs -
PERIOD_1;
void stop_stall_emulation()
void estimate_state(double rpm)
static const constexpr double PERIOD_2
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
void start_stall_emulation()
IceStatusSensor(ros::NodeHandle *nh, const char *topic, double period)
ros::Publisher publisher_
static const constexpr double PERIOD_1
static const constexpr double WORKING_RPM
static const constexpr double STARTING_RPM
ros::Publisher _status_publisher
void emulate_normal_mode(double rpm)
ros::NodeHandle * node_handler_
void emulate_stall_mode()
static const constexpr double PERIOD_3
static const constexpr double PERIOD_23
inno_vtol_dynamics
Author(s): Roman Fedorenko, Dmitry Ponomarev, Ezra Tal, Winter Guerra
autogenerated on Mon Dec 9 2024 03:13:35