]> defiant.homedns.org Git - ros_wild_thumper.git/commitdiff
configuration of odometry covariance via dynamic reconfigure
authorErik Andresen <erik@vontaene.de>
Mon, 23 Jan 2017 12:25:52 +0000 (13:25 +0100)
committerErik Andresen <erik@vontaene.de>
Mon, 23 Jan 2017 12:25:52 +0000 (13:25 +0100)
config/wt_node.cfg
launch/3dsensor.launch
scripts/wt_node.py

index 45ad4ebb65f1ec16c85a39a9d1a85912742c2dea..598362246fc1ee0586a544ffd9e44523b4824ef1 100755 (executable)
@@ -6,5 +6,7 @@ gen = ParameterGenerator()
 
 gen.add("range_sensor_clip",   bool_t,         0, "Clip range sensor values to max range", True)
 gen.add("range_sensor_max",    double_t,       0, "Range sensor max range", 0.5, 0.4, 6)
+gen.add("odom_covar_xy",       double_t,       0, "Odometry covariance: translation", 1e-2, 1e-6, 1)
+gen.add("odom_covar_angle",    double_t,       0, "Odometry covariance: rotation", 0.25, 1e-6, 6.2832)
 
 exit(gen.generate("wild_thumper", "wild_thumper", "WildThumper"))
index 116a631d7fd19f7017f2e0692f41134138c03257..4227fe96f862a5596c03a81c0f9ec4be3d4f5eca 100644 (file)
@@ -4,6 +4,7 @@
                <arg name="depth_registration" value="true" />
        </include>
        <param name="/camera/driver/depth_mode" value="11" />
+       <param name="/camera/driver/data_skip" value="1" />
 
        <node pkg="nodelet" type="nodelet" name="depthimage_to_laserscan" args="load depthimage_to_laserscan/DepthImageToLaserScanNodelet /camera/camera_nodelet_manager" output="screen">
                <remap from="/camera/image" to="/camera/depth/image"/>
index 7254c1d38ad4573961862f0af7850e87872d417b..2aa98a24b78d416da53ef8616dde5463eaf31628 100755 (executable)
@@ -102,6 +102,8 @@ class MoveBase:
        def execute_dyn_reconf(self, config, level):
                self.bClipRangeSensor = config["range_sensor_clip"]
                self.range_sensor_max = config["range_sensor_max"]
+               self.odom_covar_xy = config["odom_covar_xy"]
+               self.odom_covar_angle = config["odom_covar_angle"]
                return config
 
        def set_motor_handicap(self, front, aft): # percent
@@ -212,24 +214,19 @@ class MoveBase:
                odom.pose.pose.orientation.y = odom_quat[1]
                odom.pose.pose.orientation.z = odom_quat[2]
                odom.pose.pose.orientation.w = odom_quat[3]
-               odom.pose.covariance[0] = 1e-3 # x
-               odom.pose.covariance[7] = 1e-3 # y
-               odom.pose.covariance[14] = 1e6 # z
-               odom.pose.covariance[21] = 1e6 # rotation about X axis
-               odom.pose.covariance[28] = 1e6 # rotation about Y axis
-               odom.pose.covariance[35] = 0.03 # rotation about Z axis
+               odom.pose.covariance[0] = self.odom_covar_xy # x
+               odom.pose.covariance[7] = self.odom_covar_xy # y
+               odom.pose.covariance[14] = 99999 # z
+               odom.pose.covariance[21] = 99999 # rotation about X axis
+               odom.pose.covariance[28] = 99999 # rotation about Y axis
+               odom.pose.covariance[35] = self.odom_covar_angle # rotation about Z axis
 
                # set the velocity
                odom.child_frame_id = "base_footprint"
                odom.twist.twist.linear.x = speed_trans
                odom.twist.twist.linear.y = 0.0
                odom.twist.twist.angular.z = speed_rot
-               odom.twist.covariance[0] = 1e-3 # x
-               odom.twist.covariance[7] = 1e-3 # y
-               odom.twist.covariance[14] = 1e6 # z
-               odom.twist.covariance[21] = 1e6 # rotation about X axis
-               odom.twist.covariance[28] = 1e6 # rotation about Y axis
-               odom.twist.covariance[35] = 0.03 # rotation about Z axis
+               odom.twist.covariance = odom.pose.covariance
 
                # publish the message
                self.pub_odom.publish(odom)