From: Erik Andresen Date: Thu, 3 Sep 2015 17:53:14 +0000 (+0200) Subject: simulation/gazebo: added controller for imu, range sensors and diff X-Git-Url: https://defiant.homedns.org/gitweb/?a=commitdiff_plain;h=fef837ff325499eccd07828f2f1ce104727d37db;p=ros_wild_thumper.git simulation/gazebo: added controller for imu, range sensors and diff drive --- diff --git a/config/control.yaml b/config/control.yaml new file mode 100644 index 0000000..648218d --- /dev/null +++ b/config/control.yaml @@ -0,0 +1,41 @@ +joint_state_controller: + type: "joint_state_controller/JointStateController" + publish_rate: 20 + +diff_drive_controller: + type: "diff_drive_controller/DiffDriveController" + left_wheel: ['front_left_wheel_joint', 'rear_left_wheel_joint'] + right_wheel: ['front_right_wheel_joint', 'rear_right_wheel_joint'] + publish_rate: 20 + pose_covariance_diagonal: [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 0.03] + twist_covariance_diagonal: [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 0.03] + cmd_vel_timeout: 1000000000 + + # Base frame_id + base_frame_id: base_footprint + + # Odometry fused with IMU is published by robot_localization, so + # no need to publish a TF based on encoders alone. + enable_odom_tf: false + + # Hardware provides wheel velocities + estimate_velocity_from_position: false + + # Wheel separation and radius multipliers + wheel_separation_multiplier: 1.0 # default: 1.0 + wheel_radius_multiplier : 1.0 # default: 1.0 + + # Velocity and acceleration limits + # Whenever a min_* is unspecified, default to -max_* + linear: + x: + has_velocity_limits : true + max_velocity : 1.5 # m/s + has_acceleration_limits: true + max_acceleration : 2.0 # m/s^2 + angular: + z: + has_velocity_limits : true + max_velocity : 3.0 # rad/s + has_acceleration_limits: true + max_acceleration : 3.0 # rad/s^2 diff --git a/launch/gazebo.launch b/launch/gazebo.launch index 219529a..b93b250 100644 --- a/launch/gazebo.launch +++ b/launch/gazebo.launch @@ -1,5 +1,8 @@ + + + @@ -12,7 +15,23 @@ + + + + + + + + + + + + + + + + diff --git a/scripts/wt_node.py b/scripts/wt_node.py index 72c0412..96d0768 100755 --- a/scripts/wt_node.py +++ b/scripts/wt_node.py @@ -39,15 +39,18 @@ class MoveBase: rate = rospy.Rate(20.0) reset_val = self.get_reset() rospy.loginfo("Reset Status: 0x%x" % reset_val) + i = 0 while not rospy.is_shutdown(): #print struct.unpack(">B", i2c_read_reg(0x50, 0xA2, 1))[0] # count test self.get_tle_err() self.get_odom() self.get_voltage() - self.get_dist_forward() - self.get_dist_backward() - self.get_dist_left() - self.get_dist_right() + if i % 2: + self.get_dist_forward() + self.get_dist_backward() + self.get_dist_left() + self.get_dist_right() + i+=1 rate.sleep() def set_motor_handicap(self, front, aft): # percent diff --git a/urdf/wild_thumper.urdf.xacro b/urdf/wild_thumper.urdf.xacro index cf2c672..733a51d 100644 --- a/urdf/wild_thumper.urdf.xacro +++ b/urdf/wild_thumper.urdf.xacro @@ -26,7 +26,7 @@ - + @@ -170,47 +170,84 @@ - - - 0.001 - - - 0.001 - + + transmission_interface/SimpleTransmission + + VelocityJointInterface + + + VelocityJointInterface + 1 + + + - - - - + + + + - + / - aft_left_wheel_joint, aft_right_wheel_joint, front_left_wheel_joint, front_right_wheel_joint - 10.0 - true + gazebo_ros_control/DefaultRobotHWSim - - / + true - 10.0 - aft_right_wheel_joint - aft_left_wheel_joint - 0.252 - 0.12 - 5.0 - cmd_vel - odom - odom - base_footprint - Info - false - true - 0.0 - world - true + 20.0 + base_imu_link + imu + 0.05 + base_imu_link + 0 0 0 + 0 0 0 + + + + + 0 0 0 0 0 0 + ${update_rate} + false + + + + 5 + 1 + -${fov/2} + ${fov/2} + + + 5 + 1 + -${fov/2} + ${fov/2} + + + + ${minRange} + ${maxRange} + 0.01 + + + + 0.005 + true + ${update_rate} + ${ros_topic} + ${name} + ${fov} + ${radiation} + + + + + + + + + diff --git a/worlds/test.world b/worlds/test.world index 8fc420c..c0c2ce1 100644 --- a/worlds/test.world +++ b/worlds/test.world @@ -12,5 +12,9 @@ gas_station -2.0 7.0 0 0 0 0 + + 0.02 + 50 +