From 67ce0bb517f49851a8421981b074d472c8dc9624 Mon Sep 17 00:00:00 2001 From: Erik Andresen Date: Mon, 23 Jan 2017 13:25:52 +0100 Subject: [PATCH] configuration of odometry covariance via dynamic reconfigure --- config/wt_node.cfg | 2 ++ launch/3dsensor.launch | 1 + scripts/wt_node.py | 21 +++++++++------------ 3 files changed, 12 insertions(+), 12 deletions(-) diff --git a/config/wt_node.cfg b/config/wt_node.cfg index 45ad4eb..5983622 100755 --- a/config/wt_node.cfg +++ b/config/wt_node.cfg @@ -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")) diff --git a/launch/3dsensor.launch b/launch/3dsensor.launch index 116a631..4227fe9 100644 --- a/launch/3dsensor.launch +++ b/launch/3dsensor.launch @@ -4,6 +4,7 @@ + diff --git a/scripts/wt_node.py b/scripts/wt_node.py index 7254c1d..2aa98a2 100755 --- a/scripts/wt_node.py +++ b/scripts/wt_node.py @@ -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) -- 2.39.2