Skip to content

Commit

Permalink
revert battery message commit (#77)
Browse files Browse the repository at this point in the history
ref: 45a7ae4
  • Loading branch information
jack-oquin committed Jul 1, 2017
1 parent fcb5ecd commit e8505b4
Show file tree
Hide file tree
Showing 8 changed files with 19 additions and 17 deletions.
2 changes: 1 addition & 1 deletion segbot_bringup/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@
<!-- segway_v3 packages commented out until released publicly -->
<!-- <exec_depend>segway_msgs</exec_depend> -->
<!-- <exec_depend>segway_ros</exec_depend> -->
<exec_depend>sensor_msgs</exec_depend>
<exec_depend>smart_battery_msgs</exec_depend>
<exec_depend>stop_base</exec_depend>
<exec_depend>tf</exec_depend>
<exec_depend>xacro</exec_depend>
Expand Down
2 changes: 1 addition & 1 deletion segbot_bringup/scripts/segbot_v3_controller
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ from nav_msgs.msg import Odometry
from segway_msgs.msg import ConfigCmd
from segway_msgs.msg import Status
from segway_msgs.msg import AuxPower
from sensor_msgs.msg import BatteryState
from smart_battery_msgs.msg import SmartBatteryStatus

class Controller():

Expand Down
2 changes: 2 additions & 0 deletions segbot_sensors/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@ find_package(catkin REQUIRED
roscpp
roslint
sensor_msgs
smart_battery_msgs
std_msgs
tf)

Expand All @@ -34,6 +35,7 @@ catkin_package(
nodelet
pcl_ros
sensor_msgs
smart_battery_msgs
std_msgs
tf
INCLUDE_DIRS
Expand Down
6 changes: 3 additions & 3 deletions segbot_sensors/README.rst
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ data from various attached sensors into ROS messages.
Published topics
''''''''''''''''

``battery0`` (`sensor_msgs/BatteryState`_)
``battery0`` (`smart_battery_msgs/SmartBatteryStatus`_)
Main segbot battery voltage measurements.

``imu0`` (`sensor_msgs/Imu`_)
Expand Down Expand Up @@ -79,5 +79,5 @@ To run both the ``arduino_driver`` and this node::
http://docs.ros.org/api/sensor_msgs/html/msg/PointCloud2.html
.. _`sensor_msgs/Range`:
http://docs.ros.org/api/sensor_msgs/html/msg/Range.html
.. _`sensor_msgs/BatteryState`:
http://docs.ros.org/api/sensor_msgs/html/msg/BatteryState.html
.. _`smart_battery_msgs/SmartBatteryStatus`:
http://docs.ros.org/api/smart_battery_msgs/html/msg/SmartBatteryStatus.html
1 change: 1 addition & 0 deletions segbot_sensors/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
<depend>pluginlib</depend>
<depend>roscpp</depend>
<depend>sensor_msgs</depend>
<depend>smart_battery_msgs</depend>
<depend>std_msgs</depend>
<depend>tf</depend>

Expand Down
4 changes: 2 additions & 2 deletions segbot_sensors/src/segbot_sensors/battery_diagnostics.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
#include "diagnostic_msgs/DiagnosticStatus.h"
#include "diagnostic_msgs/DiagnosticArray.h"
#include "diagnostic_msgs/KeyValue.h"
#include "sensor_msgs/BatteryState.h"
#include "smart_battery_msgs/SmartBatteryStatus.h"
#include <ros/package.h>
#include <vector>
#include <cmath>
Expand All @@ -27,7 +27,7 @@
float voltage;
double alpha;

void voltageCallback(const sensor_msgs::BatteryState::ConstPtr& msg) {
void voltageCallback(const smart_battery_msgs::SmartBatteryStatus::ConstPtr& msg) {
voltage = alpha * msg->voltage + (1.0 - alpha) * voltage;
}

Expand Down
6 changes: 3 additions & 3 deletions segbot_sensors/src/segbot_sensors/fake_volt_pub.cpp
Original file line number Diff line number Diff line change
@@ -1,17 +1,17 @@
#include "ros/ros.h"
#include "std_msgs/String.h"
#include "sensor_msgs/BatteryState.h"
#include "smart_battery_msgs/SmartBatteryStatus.h"
#include <sstream>

int main(int argc, char **argv){
ros::init(argc, argv, "talker");
ros::NodeHandle n;
ros::Publisher chatter_pub = n.advertise<sensor_msgs::BatteryState>("/battery0", 1);
ros::Publisher chatter_pub = n.advertise<smart_battery_msgs::SmartBatteryStatus>("/battery0", 1);
ros::Rate loop_rate(10);

int count = 0;
while (ros::ok()){
sensor_msgs::BatteryState stat;
smart_battery_msgs::SmartBatteryStatus stat;
stat.voltage = 10.9;
chatter_pub.publish(stat);
ros::spinOnce();
Expand Down
13 changes: 6 additions & 7 deletions segbot_sensors/src/segbot_sensors/voltmeter.py
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@
"""
This module handles voltage messages from the Arduino Mega 2560
mounted on BWI segbots, publishing them as ROS
sensor_msgs/BatteryState messages.
smart_battery_msgs/SmartBatteryStatus messages.
"""

# enable some python3 compatibility options:
Expand All @@ -43,7 +43,7 @@
import re

import rospy
from sensor_msgs.msg import BatteryState
from smart_battery_msgs.msg import SmartBatteryStatus
from geometry_msgs.msg import Vector3


Expand All @@ -56,16 +56,15 @@ def __init__(self):
""" Extracts voltage reading from the Arduino serial message.
:returns: voltage data string reported, may be empty.
"""
self.pub = rospy.Publisher('battery0', BatteryState,
self.pub = rospy.Publisher('battery0', SmartBatteryStatus,
queue_size=1)
# initialize constant fields in battery message
self.battery = BatteryState(
current=float('nan'),
self.battery = SmartBatteryStatus(
rate=float('nan'),
charge=float('nan'),
capacity=float('nan'),
design_capacity=float('nan'),
percentage=float('nan'),
power_supply_status=BatteryState.POWER_SUPPLY_STATUS_DISCHARGING,
charge_state=SmartBatteryStatus.DISCHARGING,
present=1)

def publish(self, serial_msg):
Expand Down

0 comments on commit e8505b4

Please sign in to comment.