3 #include <dynamic_reconfigure/server.h> 4 #include <multiwii/UpdateRatesConfig.h> 6 #include <std_msgs/UInt16.h> 7 #include <std_msgs/UInt32.h> 8 #include <std_msgs/UInt8MultiArray.h> 9 #include <std_msgs/Bool.h> 10 #include <std_msgs/Float64.h> 12 #include <geometry_msgs/PoseStamped.h> 13 #include <geometry_msgs/Vector3.h> 15 #include <sensor_msgs/BatteryState.h> 16 #include <sensor_msgs/Imu.h> 17 #include <sensor_msgs/MagneticField.h> 19 #include <mavros_msgs/RCIn.h> 20 #include <mavros_msgs/RCOut.h> 21 #include <mavros_msgs/OverrideRCIn.h> 22 #include <mavros_msgs/ActuatorControl.h> 23 #include <mavros_msgs/CommandBool.h> 30 #include <Eigen/Geometry> 33 return deg/180.0 * M_PI;
37 return rad/M_PI * 180.0;
51 dynamic_reconfigure::Server<multiwii::UpdateRatesConfig>
dyn_conf_srv;
78 if(nh.
getParam(
"standard_gravity", std_grav))
79 this->si_unit_1g = std_grav;
81 ROS_ERROR(
"Parameter 'standard_gravity' not set.");
85 this->acc_1g = acc_1g;
90 if(nh.
getParam(
"gyro_unit", gyro_unit))
91 this->gyro_unit = gyro_unit;
93 ROS_ERROR(
"Parameter 'gyro_unit' not set.");
96 if(nh.
getParam(
"magn_gain", magn_gain))
97 this->magn_gain = magn_gain;
99 ROS_ERROR(
"Parameter 'magn_gain' not set.");
115 int baudrate = 115200;
117 if(!nh.
getParam(
"baudrate", baudrate)) {
118 ROS_ERROR(
"Parameter 'baudrate' not set. Using default baudrate of %i", baudrate);
122 ROS_ERROR(
"'baudrate' must be positive!");
126 ROS_INFO(
"Connected to FCU at %s", device.c_str());
129 ROS_ERROR(
"Parameter 'device' not set.");
135 imu_pub = nh.
advertise<sensor_msgs::Imu>(
"imu/data", 1);
136 magn_pub = nh.
advertise<sensor_msgs::MagneticField>(
"imu/mag", 1);
137 pose_stamped_pub = nh.
advertise<geometry_msgs::PoseStamped>(
"local_position/pose", 1);
138 rpy_pub = nh.
advertise<geometry_msgs::Vector3>(
"rpy", 1);
139 rc_in_pub = nh.
advertise<mavros_msgs::RCIn>(
"rc/in", 1);
140 servo_pub = nh.
advertise<mavros_msgs::RCOut>(
"rc/servo", 1);
141 motors_pub = nh.
advertise<mavros_msgs::RCOut>(
"motors", 1);
142 battery_pub = nh.
advertise<sensor_msgs::BatteryState>(
"battery",1);
143 heading_pub = nh.
advertise<std_msgs::Float64>(
"global_position/compass_hdg",1);
144 altitude_pub = nh.
advertise<std_msgs::Float64>(
"global_position/rel_alt",1);
145 sonar_altitude_pub = nh.
advertise<std_msgs::Float64>(
"global_position/sonar_alt", 1);
164 const std::map<msp::ID, double> msp_rates = {
176 for(
const auto& r : msp_rates) {
191 sensor_msgs::Imu imu_msg;
193 imu_msg.header.frame_id =
"multiwii";
196 imu_msg.linear_acceleration.x = imu.
acc[0];
197 imu_msg.linear_acceleration.y = imu.
acc[1];
198 imu_msg.linear_acceleration.z = imu.
acc[2];
206 const Eigen::Vector3d magn(imu.
mag[0], imu.
mag[1], imu.
mag[2]);
207 const Eigen::Vector3d lin_acc(imu.
acc[0], imu.
acc[1], imu.
acc[2]);
211 rot.col(0) = lin_acc.cross(magn).cross(lin_acc).normalized();
212 rot.col(1) = lin_acc.cross(magn).normalized();
213 rot.col(2) = lin_acc.normalized();
215 const Eigen::Quaterniond orientation(rot);
216 imu_msg.orientation.x = orientation.x();
217 imu_msg.orientation.y = orientation.y();
218 imu_msg.orientation.z = orientation.z();
219 imu_msg.orientation.w = orientation.w();
226 sensor_msgs::MagneticField mag_msg;
230 mag_msg.magnetic_field.x = imu.
mag[0];
231 mag_msg.magnetic_field.y = imu.
mag[1];
232 mag_msg.magnetic_field.z = imu.
mag[2];
238 std_msgs::Float64 heading;
239 heading.data =
rad2deg(std::atan2(
double(imu.
mag[0]),
double(imu.
mag[1])));
246 rot = Eigen::AngleAxisf(
deg2rad(attitude.
roll), Eigen::Vector3f::UnitX())
247 * Eigen::AngleAxisf(
deg2rad(attitude.
pitch), Eigen::Vector3f::UnitY())
248 * Eigen::AngleAxisf(
deg2rad(attitude.
yaw), Eigen::Vector3f::UnitZ());
250 const Eigen::Quaternionf quat(rot);
252 geometry_msgs::PoseStamped pose_stamped;
254 pose_stamped.header.frame_id =
"multiwii";
255 pose_stamped.pose.orientation.x = quat.x();
256 pose_stamped.pose.orientation.y = quat.y();
257 pose_stamped.pose.orientation.z = quat.z();
258 pose_stamped.pose.orientation.w = quat.w();
260 pose_stamped_pub.
publish(pose_stamped);
269 multiwii_transform.
setRotation(multiwii_quaternion);
274 geometry_msgs::Vector3 rpy;
275 rpy.x = attitude.
roll;
276 rpy.y = attitude.
pitch;
277 rpy.z = attitude.
yaw;
282 std_msgs::Float64 alt;
291 multiwii_transform.
setRotation(multiwii_quaternion);
298 mavros_msgs::RCIn rc_msg;
306 mavros_msgs::RCOut rc;
307 for(
const uint16_t
s : servo.
servo) {
308 rc.channels.push_back(s);
314 mavros_msgs::RCOut motor_out;
315 for(
const uint16_t m : motor.
motor) {
316 motor_out.channels.push_back(m);
322 sensor_msgs::BatteryState battery;
324 battery.voltage = analog.
vbat;
331 std_msgs::Float64 alt;
333 sonar_altitude_pub.
publish(alt);
340 multiwii_transform.
setRotation(multiwii_quaternion);
351 fcu->
setRc(rc.channels[0], rc.channels[1], rc.channels[2], rc.channels[3],
352 rc.channels[4], rc.channels[5], rc.channels[6], rc.channels[7]);
356 std::vector<uint16_t> channels;
357 for(
const uint16_t c : rc.channels) { channels.push_back(c); }
358 fcu->
setRc(channels);
367 std::array<uint16_t,msp::msg::N_MOTOR> motor_values;
368 for(
uint i(0); i<motor_values.size(); i++) {
369 motor_values[i] = 1000+abs(motors.controls[i]*1000);
376 int main(
int argc,
char **argv) {
385 std::cout<<
"MSP ready"<<std::endl;
void onMotor(const msp::msg::Motor &motor)
double deg2rad(const double deg)
ros::Subscriber rc_in_sub
ros::Publisher pose_stamped_pub
void publish(const boost::shared_ptr< M > &message) const
std::array< uint16_t, N_SERVO > servo
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::Subscriber motor_control_sub
std::vector< uint16_t > channels
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void onImu(const msp::msg::RawImu &imu)
callbacks for published messages
tf::TransformBroadcaster tf_broadcaster
std::array< Value< int16_t >, 3 > mag
bool hasSubscription(const msp::ID &id) const
void onAttitude(const msp::msg::Attitude &attitude)
void onServo(const msp::msg::Servo &servo)
ROSCPP_DECL void spin(Spinner &spinner)
void motor_control(const mavros_msgs::ActuatorControl &motors)
int main(int argc, char **argv)
void setRPY(const tfScalar &roll, const tfScalar &pitch, const tfScalar &yaw)
ros::Publisher heading_pub
void onSonarAltitude(const msp::msg::SonarAltitude &sonar_altitude)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
std::array< Value< int16_t >, 3 > gyro
ros::Publisher battery_pub
bool setMotors(const std::array< uint16_t, msp::msg::N_MOTOR > &motor_values)
double rad2deg(const double rad)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
std::array< uint16_t, N_MOTOR > motor
std::array< Value< int16_t >, 3 > acc
ros::Publisher altitude_pub
void rc_override_raw(const mavros_msgs::OverrideRCIn &rc)
std::shared_ptr< msp::client::SubscriptionBase > getSubscription(const msp::ID &id)
bool setRc(const uint16_t roll, const uint16_t pitch, const uint16_t yaw, const uint16_t throttle, const uint16_t aux1=1000, const uint16_t aux2=1000, const uint16_t aux3=1000, const uint16_t aux4=1000, const std::vector< uint16_t > auxs=std::vector< uint16_t >())
ros::Subscriber rc_in_sub2
void onAnalog(const msp::msg::Analog &analog)
void setDynamicConfigureCallback()
setDynamicConfigureCallback set the callback This will call the callback once for initialisation ...
fcu::FlightController & fc() const
void onRc(const msp::msg::Rc &rc)
bool getParam(const std::string &key, std::string &s) const
bool connect(const std::string &device, const size_t baudrate=115200, const double &timeout=0.0, const bool print_info=false)
ros::Publisher sonar_altitude_pub
ROSCPP_DECL void shutdown()
std::shared_ptr< msp::client::SubscriptionBase > subscribe(void(C::*callback)(const T &), C *context, const double tp=0.0)
Value< uint32_t > altitude_cm
void dynconf_callback(multiwii::UpdateRatesConfig &config, uint32_t)
fcu::FlightController * fcu
std::string tf_base_frame
ros::Publisher motors_pub
void rc_override_AERT1234(const mavros_msgs::OverrideRCIn &rc)
callbacks for subscribed messages
dynamic_reconfigure::Server< multiwii::UpdateRatesConfig > dyn_conf_srv
void onAltitude(const msp::msg::Altitude &altitude)