]> defiant.homedns.org Git - ros_wild_thumper.git/commitdiff
added diagnostic msg
authorErik Andresen <erik@vontaene.de>
Fri, 14 Aug 2015 01:03:43 +0000 (01:03 +0000)
committerErik Andresen <erik@vontaene.de>
Fri, 14 Aug 2015 01:03:43 +0000 (01:03 +0000)
cfg/analyzers.yaml [new file with mode: 0644]
package.xml
scripts/move_base.py
wild_thumper.launch

diff --git a/cfg/analyzers.yaml b/cfg/analyzers.yaml
new file mode 100644 (file)
index 0000000..24193de
--- /dev/null
@@ -0,0 +1,6 @@
+analyzers:
+        motors:
+                type: GenericAnalyzer
+                path: Motors
+                startswith: 'Motor'
+                find_and_remove_prefix: motor
index 395909f1a06710e945bc1733c8e9bb4d8d56988c..6911afefac1fab5d77cd471cb299f49bcc33cab7 100644 (file)
@@ -45,6 +45,7 @@
   <build_depend>roscpp</build_depend>
   <build_depend>std_msgs</build_depend>
   <build_depend>image_transport</build_depend>
   <build_depend>roscpp</build_depend>
   <build_depend>std_msgs</build_depend>
   <build_depend>image_transport</build_depend>
+  <run_depend>hector_sensors_description</run_depend>
 
   <!-- The export tag contains other, unspecified, tags -->
   <export>
 
   <!-- The export tag contains other, unspecified, tags -->
   <export>
index ae15b380ddd1cb3afc1ae05ad1f162b22fb9377a..0f0bc190fcd7030a6cbdf1b9824a93f309e7e689 100755 (executable)
@@ -8,6 +8,7 @@ from i2c import *
 from math import *
 from geometry_msgs.msg import Twist
 from nav_msgs.msg import Odometry
 from math import *
 from geometry_msgs.msg import Twist
 from nav_msgs.msg import Odometry
+from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus, KeyValue
 
 WHEEL_DIST = 0.248
 
 
 WHEEL_DIST = 0.248
 
@@ -17,6 +18,7 @@ class MoveBase:
                rospy.Subscriber("cmd_vel", Twist, self.cmdVelReceived)
                self.tf_broadcaster = tf.broadcaster.TransformBroadcaster()
                self.pub_odom = rospy.Publisher("odom", Odometry, queue_size=16)
                rospy.Subscriber("cmd_vel", Twist, self.cmdVelReceived)
                self.tf_broadcaster = tf.broadcaster.TransformBroadcaster()
                self.pub_odom = rospy.Publisher("odom", Odometry, queue_size=16)
+               self.pub_diag = rospy.Publisher("diagnostics", DiagnosticArray, queue_size=16)
                self.set_speed(0, 0)
                rospy.loginfo("Init done")
                i2c_write_reg(0x50, 0x90, struct.pack("BB", 1, 1)) # switch direction
                self.set_speed(0, 0)
                rospy.loginfo("Init done")
                i2c_write_reg(0x50, 0x90, struct.pack("BB", 1, 1)) # switch direction
@@ -25,6 +27,7 @@ class MoveBase:
        def run(self):
                rate = rospy.Rate(20.0)
                while not rospy.is_shutdown():
        def run(self):
                rate = rospy.Rate(20.0)
                while not rospy.is_shutdown():
+                       self.get_tle_err()
                        #self.get_odom()
                        #self.get_dist_forward()
                        #self.get_dist_backward()
                        #self.get_odom()
                        #self.get_dist_forward()
                        #self.get_dist_backward()
@@ -32,6 +35,25 @@ class MoveBase:
                        #self.get_dist_right()
                        rate.sleep()
 
                        #self.get_dist_right()
                        rate.sleep()
 
+       def get_tle_err(self):
+               err = struct.unpack(">B", i2c_read_reg(0x50, 0x94, 1))[0]
+               
+               msg = DiagnosticArray()
+               msg.header.stamp = rospy.Time.now()
+               stat = DiagnosticStatus()
+               stat.name = "Motor: Error Status"
+               stat.level = DiagnosticStatus.OK if not err else DiagnosticStatus.ERROR
+               stat.message = "OK" if not err else "Error"
+
+               stat.values.append(KeyValue("Motor 1", str(bool(err & (1 << 0)))))
+               stat.values.append(KeyValue("Motor 2", str(bool(err & (1 << 1)))))
+               stat.values.append(KeyValue("Motor 3", str(bool(err & (1 << 2)))))
+               stat.values.append(KeyValue("Motor 4", str(bool(err & (1 << 3)))))
+
+               msg.status.append(stat)
+               self.pub_diag.publish(msg)
+
+
        def get_odom(self):
                posx, posy, angle = struct.unpack(">fff", i2c_read_reg(0x50, 0x40, 12))
                speed_trans, speed_rot = struct.unpack(">ff", i2c_read_reg(0x50, 0x38, 8))
        def get_odom(self):
                posx, posy, angle = struct.unpack(">fff", i2c_read_reg(0x50, 0x40, 12))
                speed_trans, speed_rot = struct.unpack(">ff", i2c_read_reg(0x50, 0x38, 8))
index 2a3bb4aac3757e88ac73945feb48d8824bc1053c..8d7c7137c7446e17bcaa5ade444dd671ea28e3c0 100644 (file)
@@ -3,4 +3,8 @@
        <param name="robot_description" command="$(find xacro)/xacro.py $(find wild_thumper)/urdf/wild_thumper.urdf.xacro" />
 
        <node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" />
        <param name="robot_description" command="$(find xacro)/xacro.py $(find wild_thumper)/urdf/wild_thumper.urdf.xacro" />
 
        <node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" />
+
+       <node pkg="diagnostic_aggregator" type="aggregator_node" name="diagnostic_aggregator" >
+               <rosparam command="load" file="$(find wild_thumper)/cfg/analyzers.yaml" />
+       </node>
 </launch>
 </launch>