From: Erik Andresen Date: Fri, 14 Aug 2015 01:03:43 +0000 (+0000) Subject: added diagnostic msg X-Git-Url: https://defiant.homedns.org/gitweb/?a=commitdiff_plain;h=6a8af73159db6b0af7382a22dae0b3b18295120f;p=ros_wild_thumper.git added diagnostic msg --- diff --git a/cfg/analyzers.yaml b/cfg/analyzers.yaml new file mode 100644 index 0000000..24193de --- /dev/null +++ b/cfg/analyzers.yaml @@ -0,0 +1,6 @@ +analyzers: + motors: + type: GenericAnalyzer + path: Motors + startswith: 'Motor' + find_and_remove_prefix: motor diff --git a/package.xml b/package.xml index 395909f..6911afe 100644 --- a/package.xml +++ b/package.xml @@ -45,6 +45,7 @@ roscpp std_msgs image_transport + hector_sensors_description diff --git a/scripts/move_base.py b/scripts/move_base.py index ae15b38..0f0bc19 100755 --- a/scripts/move_base.py +++ b/scripts/move_base.py @@ -8,6 +8,7 @@ from i2c import * 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 @@ -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) + 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 @@ -25,6 +27,7 @@ class MoveBase: 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() @@ -32,6 +35,25 @@ class MoveBase: #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)) diff --git a/wild_thumper.launch b/wild_thumper.launch index 2a3bb4a..8d7c713 100644 --- a/wild_thumper.launch +++ b/wild_thumper.launch @@ -3,4 +3,8 @@ + + + +