battery topic type changed to sensor_msgs

This commit is contained in:
vivek-shankar 2018-06-14 13:08:32 -04:00
parent 44212c8fcd
commit 6d52a57dcd
2 changed files with 4 additions and 3 deletions

View File

@ -12,6 +12,7 @@
#include "mavros_msgs/SetMode.h"
#include "mavros_msgs/State.h"
#include "mavros_msgs/BatteryStatus.h"
#include "sensor_msgs/BatteryState.h"
#include "mavros_msgs/Mavlink.h"
#include "mavros_msgs/PositionTarget.h"
#include "sensor_msgs/NavSatStatus.h"
@ -205,7 +206,7 @@ private:
double gps_r_lat);
/*battery status callback */
void battery(const mavros_msgs::BatteryStatus::ConstPtr& msg);
void battery(const sensor_msgs::BatteryState::ConstPtr& msg);
/*flight extended status callback*/
void flight_extended_status_update(const mavros_msgs::ExtendedState::ConstPtr& msg);

View File

@ -836,12 +836,12 @@ void roscontroller::gps_convert_ned(float& ned_x, float& ned_y, double gps_t_lon
ned_y = DEG2RAD(d_lon) * EARTH_RADIUS * cos(DEG2RAD(gps_t_lat));
};
void roscontroller::battery(const mavros_msgs::BatteryStatus::ConstPtr& msg)
void roscontroller::battery(const sensor_msgs::BatteryState::ConstPtr& msg)
/*
/ Update battery status into BVM from subscriber
/------------------------------------------------------*/
{
buzzuav_closures::set_battery(msg->voltage, msg->current, msg->remaining);
buzzuav_closures::set_battery(msg->voltage, msg->current, msg->percentage);
// DEBUG
// ROS_INFO("voltage : %d current : %d remaining : %d",msg->voltage,
// msg->current, msg ->remaining);