reverted previous commit change of battery topic
This commit is contained in:
parent
b996694976
commit
cffea220ae
|
@ -11,8 +11,8 @@
|
||||||
#include "mavros_msgs/ExtendedState.h"
|
#include "mavros_msgs/ExtendedState.h"
|
||||||
#include "mavros_msgs/SetMode.h"
|
#include "mavros_msgs/SetMode.h"
|
||||||
#include "mavros_msgs/State.h"
|
#include "mavros_msgs/State.h"
|
||||||
#include "mavros_msgs/BatteryStatus.h"
|
//#include "mavros_msgs/BatteryStatus.h"
|
||||||
//#include "sensor_msgs/BatteryState.h"
|
#include "sensor_msgs/BatteryState.h"
|
||||||
#include "mavros_msgs/Mavlink.h"
|
#include "mavros_msgs/Mavlink.h"
|
||||||
#include "mavros_msgs/PositionTarget.h"
|
#include "mavros_msgs/PositionTarget.h"
|
||||||
#include "sensor_msgs/NavSatStatus.h"
|
#include "sensor_msgs/NavSatStatus.h"
|
||||||
|
@ -240,7 +240,7 @@ private:
|
||||||
double gps_r_lat);
|
double gps_r_lat);
|
||||||
|
|
||||||
/*battery status callback */
|
/*battery status callback */
|
||||||
void battery(const mavros_msgs::BatteryStatus::ConstPtr& msg);
|
void battery(const sensor_msgs::BatteryState::ConstPtr& msg);
|
||||||
|
|
||||||
/*flight extended status callback*/
|
/*flight extended status callback*/
|
||||||
void flight_extended_status_update(const mavros_msgs::ExtendedState::ConstPtr& msg);
|
void flight_extended_status_update(const mavros_msgs::ExtendedState::ConstPtr& msg);
|
||||||
|
|
|
@ -352,7 +352,7 @@ void roscontroller::GetSubscriptionParameters(ros::NodeHandle& node_handle)
|
||||||
m_smTopic_infos.insert(pair<std::string, std::string>(topic, "sensor_msgs/LaserScan"));
|
m_smTopic_infos.insert(pair<std::string, std::string>(topic, "sensor_msgs/LaserScan"));
|
||||||
|
|
||||||
node_handle.getParam("topics/battery", topic);
|
node_handle.getParam("topics/battery", topic);
|
||||||
m_smTopic_infos.insert(pair<std::string, std::string>(topic, "mavros_msgs/BatteryStatus"));
|
m_smTopic_infos.insert(pair<std::string, std::string>(topic, "sensor_msgs/BatteryState"));
|
||||||
|
|
||||||
node_handle.getParam("topics/status", topic);
|
node_handle.getParam("topics/status", topic);
|
||||||
m_smTopic_infos.insert(pair<std::string, std::string>(topic, "mavros_msgs/State"));
|
m_smTopic_infos.insert(pair<std::string, std::string>(topic, "mavros_msgs/State"));
|
||||||
|
@ -504,7 +504,7 @@ void roscontroller::Subscribe(ros::NodeHandle& n_c)
|
||||||
{
|
{
|
||||||
flight_status_sub = n_c.subscribe(it->first, 5, &roscontroller::flight_status_update, this);
|
flight_status_sub = n_c.subscribe(it->first, 5, &roscontroller::flight_status_update, this);
|
||||||
}
|
}
|
||||||
else if (it->second == "mavros_msgs/BatteryStatus")
|
else if (it->second == "sensor_msgs/BatteryState")
|
||||||
{
|
{
|
||||||
battery_sub = n_c.subscribe(it->first, 5, &roscontroller::battery, this);
|
battery_sub = n_c.subscribe(it->first, 5, &roscontroller::battery, this);
|
||||||
}
|
}
|
||||||
|
@ -1035,13 +1035,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));
|
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
|
/ Update battery status into BVM from subscriber
|
||||||
/------------------------------------------------------*/
|
/------------------------------------------------------*/
|
||||||
{
|
{
|
||||||
// buzzuav_closures::set_battery(msg->voltage, msg->current, msg->percentage);
|
buzzuav_closures::set_battery(msg->voltage, msg->current, msg->percentage * 100.0);
|
||||||
buzzuav_closures::set_battery(msg->voltage, msg->current, msg->remaining*!00.0);
|
|
||||||
// DEBUG
|
// DEBUG
|
||||||
// ROS_INFO("voltage : %d current : %d remaining : %d",msg->voltage,
|
// ROS_INFO("voltage : %d current : %d remaining : %d",msg->voltage,
|
||||||
// msg->current, msg ->remaining);
|
// msg->current, msg ->remaining);
|
||||||
|
|
Loading…
Reference in New Issue