fix batterystate msgs type and launch file for TX1

This commit is contained in:
David St-Onge 2018-05-29 19:57:28 +00:00
parent 44280c3d91
commit f5a091f659
2 changed files with 6 additions and 6 deletions

View File

@ -11,10 +11,10 @@
#include "mavros_msgs/ExtendedState.h"
#include "mavros_msgs/SetMode.h"
#include "mavros_msgs/State.h"
#include "mavros_msgs/BatteryStatus.h"
#include "mavros_msgs/Mavlink.h"
#include "mavros_msgs/PositionTarget.h"
#include "sensor_msgs/NavSatStatus.h"
#include "sensor_msgs/BatteryState.h"
#include "mavros_msgs/WaypointPush.h"
#include "mavros_msgs/Waypoint.h"
#include "mavros_msgs/PositionTarget.h"
@ -205,7 +205,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

@ -271,7 +271,7 @@ void roscontroller::GetSubscriptionParameters(ros::NodeHandle& node_handle)
m_smTopic_infos.insert(pair<std::string, std::string>(topic, "sensor_msgs/LaserScan"));
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);
m_smTopic_infos.insert(pair<std::string, std::string>(topic, "mavros_msgs/State"));
@ -367,7 +367,7 @@ void roscontroller::Subscribe(ros::NodeHandle& n_c)
{
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);
}
@ -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*100.0);
// DEBUG
// ROS_INFO("voltage : %d current : %d remaining : %d",msg->voltage,
// msg->current, msg ->remaining);