Skip to content

Instantly share code, notes, and snippets.

@hidmic
Created January 21, 2020 14:48
Show Gist options
  • Star 0 You must be signed in to star a gist
  • Fork 0 You must be signed in to fork a gist
  • Save hidmic/dde87376f485265c2ac9bdbbb4c9e635 to your computer and use it in GitHub Desktop.
Save hidmic/dde87376f485265c2ac9bdbbb4c9e635 to your computer and use it in GitHub Desktop.
<launch>
<node pkg="tf2_ros" type="static_transform_publisher" name="base_to_imu_tf_broadcaster"
args="-0.5 0 0 1.5707963267948966 0 3.141592653589793 base_link imu_link"/>
<node pkg="tf2_ros" type="static_transform_publisher" name="imu_to_ned_tf_broadcaster"
args="0 0 0.2 0 0 0 imu_link ned_frame"/>
<node pkg="robot_localization" type="ekf_localization_node" name="ekf_node">
<param name="filter_type" value="ekf"/>
<param name="frequency" value="10.0"/>
<param name="two_d_mode" value="true"/>
<param name="odom_frame" value="odom"/>
<param name="base_link_frame" value="base_link"/>
<param name="world_frame" value="odom"/>
<param name="imu0" value="/imu"/>
<rosparam param="imu0_config">
[false, false, false,
false, false, true,
false, false, false,
true, true, true,
false, false, false]
</rosparam>
<param name="imu0_relative" value="true"/>
<param name="odom0" value="/wheel/odom" />
<rosparam param="odom0_config">
[false, false, false,
true, true, false,
false, false, false,
false, false, false,
false, false, false]
</rosparam>
<param name="publish_tf" value="true"/>
</node>
</launch>
Panels:
- Class: rviz/Displays
Help Height: 78
Name: Displays
Property Tree Widget:
Expanded:
- /Global Options1
- /Status1
- /TF1
- /TF1/Frames1
- /Odometry1
- /Odometry2
- /Odometry2/Shape1
Splitter Ratio: 0.5
Tree Height: 734
- Class: rviz/Selection
Name: Selection
- Class: rviz/Tool Properties
Expanded:
- /2D Pose Estimate1
- /2D Nav Goal1
- /Publish Point1
Name: Tool Properties
Splitter Ratio: 0.5886790156364441
- Class: rviz/Views
Expanded:
- /Current View1
Name: Views
Splitter Ratio: 0.5
- Class: rviz/Time
Experimental: false
Name: Time
SyncMode: 0
SyncSource: ""
Preferences:
PromptSaveOnExit: true
Toolbars:
toolButtonStyle: 2
Visualization Manager:
Class: ""
Displays:
- Alpha: 0.5
Cell Size: 1
Class: rviz/Grid
Color: 160; 160; 164
Enabled: true
Line Style:
Line Width: 0.029999999329447746
Value: Lines
Name: Grid
Normal Cell Count: 0
Offset:
X: 0
Y: 0
Z: 0
Plane: XY
Plane Cell Count: 10
Reference Frame: <Fixed Frame>
Value: true
- Class: rviz/TF
Enabled: true
Frame Timeout: 15
Frames:
All Enabled: false
base_link:
Value: true
imu_link:
Value: true
ned_frame:
Value: false
odom:
Value: false
Marker Scale: 0.800000011920929
Name: TF
Show Arrows: true
Show Axes: true
Show Names: true
Tree:
base_link:
imu_link:
ned_frame:
{}
odom:
{}
Update Interval: 0
Value: true
- Angle Tolerance: 0.10000000149011612
Class: rviz/Odometry
Covariance:
Orientation:
Alpha: 0.5
Color: 255; 255; 127
Color Style: Unique
Frame: Local
Offset: 1
Scale: 1
Value: true
Position:
Alpha: 0.30000001192092896
Color: 204; 51; 204
Scale: 1
Value: true
Value: false
Enabled: true
Keep: 1
Name: Odometry
Position Tolerance: 0.10000000149011612
Shape:
Alpha: 1
Axes Length: 1
Axes Radius: 0.10000000149011612
Color: 255; 25; 0
Head Length: 0.30000001192092896
Head Radius: 0.10000000149011612
Shaft Length: 1
Shaft Radius: 0.05000000074505806
Value: Arrow
Topic: /odometry/filtered
Unreliable: false
Value: true
- Angle Tolerance: 0.10000000149011612
Class: rviz/Odometry
Covariance:
Orientation:
Alpha: 0.5
Color: 255; 255; 127
Color Style: Unique
Frame: Local
Offset: 1
Scale: 1
Value: true
Position:
Alpha: 0.30000001192092896
Color: 204; 51; 204
Scale: 1
Value: true
Value: false
Enabled: true
Keep: 1
Name: Odometry
Position Tolerance: 0.10000000149011612
Shape:
Alpha: 1
Axes Length: 1
Axes Radius: 0.10000000149011612
Color: 1; 255; 81
Head Length: 0.30000001192092896
Head Radius: 0.10000000149011612
Shaft Length: 1
Shaft Radius: 0.05000000074505806
Value: Arrow
Topic: /wheel/odom
Unreliable: false
Value: true
Enabled: true
Global Options:
Background Color: 48; 48; 48
Default Light: true
Fixed Frame: odom
Frame Rate: 30
Name: root
Tools:
- Class: rviz/Interact
Hide Inactive Objects: true
- Class: rviz/MoveCamera
- Class: rviz/Select
- Class: rviz/FocusCamera
- Class: rviz/Measure
- Class: rviz/SetInitialPose
Theta std deviation: 0.2617993950843811
Topic: /initialpose
X std deviation: 0.5
Y std deviation: 0.5
- Class: rviz/SetGoal
Topic: /move_base_simple/goal
- Class: rviz/PublishPoint
Single click: true
Topic: /clicked_point
Value: true
Views:
Current:
Class: rviz/Orbit
Distance: 2.2010698318481445
Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Focal Point:
X: -0.12720155715942383
Y: 0.03638945519924164
Z: -0.06940260529518127
Focal Shape Fixed Size: true
Focal Shape Size: 0.05000000074505806
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.009999999776482582
Pitch: 0.69539874792099
Target Frame: <Fixed Frame>
Value: Orbit (rviz)
Yaw: 4.1554059982299805
Saved: ~
Window Geometry:
Displays:
collapsed: false
Height: 1025
Hide Left Dock: false
Hide Right Dock: false
QMainWindow State: 000000ff00000000fd00000004000000000000015600000367fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b00000367000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000367fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003b00000367000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073d0000003efc0100000002fb0000000800540069006d006501000000000000073d0000024400fffffffb0000000800540069006d00650100000000000004500000000000000000000004cc0000036700000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Time:
collapsed: false
Tool Properties:
collapsed: false
Views:
collapsed: false
Width: 1853
X: 67
Y: 27
import math
import rospy
from sensor_msgs.msg import Imu
from nav_msgs.msg import Odometry
import tf.transformations as tft
if __name__ == '__main__':
rospy.init_node('swinging_base_node')
imu_pub = rospy.Publisher('/imu', Imu, queue_size=10)
odom_pub = rospy.Publisher('/wheel/odom', Odometry, queue_size=10)
rate = rospy.Rate(50)
start_time = rospy.get_rostime()
while not rospy.is_shutdown():
current_time = rospy.get_rostime()
yaw_angle = math.pi/2 * math.sin(2 * math.pi * (current_time - start_time).to_sec() / 20)
yaw_velocity = math.pi/40 * math.cos(2 * math.pi * (current_time - start_time).to_sec() / 20)
imu_quat = tft.quaternion_about_axis(-yaw_angle, (0, 0, 1))
# NED -> ENU conversion
imu_quat = tft.quaternion_multiply(
imu_quat, tft.quaternion_from_euler(math.pi, 0, math.pi/2, 'sxyz')
)
odom_quat = tft.quaternion_about_axis(yaw_angle, (0, 0, 1))
imu_msg = Imu()
imu_msg.header.stamp = current_time
imu_msg.header.frame_id = 'imu_link'
imu_msg.angular_velocity.z = -yaw_velocity
imu_msg.linear_acceleration.z = -9.8
(imu_msg.orientation.x,
imu_msg.orientation.y,
imu_msg.orientation.z,
imu_msg.orientation.w) = imu_quat
imu_pub.publish(imu_msg)
odom_msg = Odometry()
odom_msg.header.stamp = current_time
odom_msg.header.frame_id = 'odom'
odom_msg.child_frame_id = 'base_link'
odom_msg.twist.twist.angular.z = yaw_velocity
(odom_msg.pose.pose.orientation.x,
odom_msg.pose.pose.orientation.y,
odom_msg.pose.pose.orientation.z,
odom_msg.pose.pose.orientation.w) = odom_quat
odom_pub.publish(odom_msg)
rate.sleep()
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment