Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
192 changes: 180 additions & 12 deletions ground_control_station/ros_ws/src/gcs_bringup/rviz/gcs.rviz
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@ Panels:
- /Global Options1
- /Status1
Splitter Ratio: 0.5
Tree Height: 555
Tree Height: 725
- Class: rviz_common/Selection
Name: Selection
- Class: rviz_common/Tool Properties
Expand Down Expand Up @@ -47,6 +47,174 @@ Visualization Manager:
Plane Cell Count: 10
Reference Frame: <Fixed Frame>
Value: true
- Class: rviz_common/Group
Displays:
- Class: rviz_default_plugins/Marker
Enabled: true
Name: Marker
Namespaces:
"": true
Topic:
Depth: 5
Durability Policy: Volatile
Filter size: 10
History Policy: Keep Last
Reliability Policy: Reliable
Value: /robot_1/vdb_mapping/vdb_map_visualization
Value: true
- Angle Tolerance: 0.10000000149011612
Class: rviz_default_plugins/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: true
Enabled: true
Keep: 100
Name: Odometry
Position Tolerance: 0.10000000149011612
Shape:
Alpha: 1
Axes Length: 1
Axes Radius: 0.30000001192092896
Color: 255; 25; 0
Head Length: 0.30000001192092896
Head Radius: 0.10000000149011612
Shaft Length: 1
Shaft Radius: 0.05000000074505806
Value: Axes
Topic:
Depth: 5
Durability Policy: Volatile
Filter size: 10
History Policy: Keep Last
Reliability Policy: Reliable
Value: /robot_1/odometry_conversion/odometry
Value: true
Enabled: true
Name: robot 1
- Class: rviz_common/Group
Displays:
- Class: rviz_default_plugins/Marker
Enabled: true
Name: Marker
Namespaces:
"": true
Topic:
Depth: 5
Durability Policy: Volatile
Filter size: 10
History Policy: Keep Last
Reliability Policy: Reliable
Value: /robot_2/vdb_mapping/vdb_map_visualization
Value: true
- Angle Tolerance: 0.10000000149011612
Class: rviz_default_plugins/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: true
Enabled: true
Keep: 100
Name: Odometry
Position Tolerance: 0.10000000149011612
Shape:
Alpha: 1
Axes Length: 1
Axes Radius: 0.30000001192092896
Color: 255; 25; 0
Head Length: 0.30000001192092896
Head Radius: 0.10000000149011612
Shaft Length: 1
Shaft Radius: 0.05000000074505806
Value: Axes
Topic:
Depth: 5
Durability Policy: Volatile
Filter size: 10
History Policy: Keep Last
Reliability Policy: Reliable
Value: /robot_2/odometry_conversion/odometry
Value: true
Enabled: true
Name: robot 2
- Class: rviz_common/Group
Displays:
- Class: rviz_default_plugins/Marker
Enabled: true
Name: Marker
Namespaces:
{}
Topic:
Depth: 5
Durability Policy: Volatile
Filter size: 10
History Policy: Keep Last
Reliability Policy: Reliable
Value: /robot_3/vdb_mapping/vdb_map_visualization
Value: true
- Angle Tolerance: 0.10000000149011612
Class: rviz_default_plugins/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: true
Enabled: true
Keep: 100
Name: Odometry
Position Tolerance: 0.10000000149011612
Shape:
Alpha: 1
Axes Length: 1
Axes Radius: 0.30000001192092896
Color: 255; 25; 0
Head Length: 0.30000001192092896
Head Radius: 0.10000000149011612
Shaft Length: 1
Shaft Radius: 0.05000000074505806
Value: Axes
Topic:
Depth: 5
Durability Policy: Volatile
Filter size: 10
History Policy: Keep Last
Reliability Policy: Reliable
Value: /robot_3/odometry_conversion/odometry
Value: true
Enabled: true
Name: robot 3
Enabled: true
Global Options:
Background Color: 48; 48; 48
Expand Down Expand Up @@ -93,33 +261,33 @@ Visualization Manager:
Views:
Current:
Class: rviz_default_plugins/Orbit
Distance: 10
Distance: 19.87488555908203
Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Focal Point:
X: 0
Y: 0
Z: 0
X: 1.4299687147140503
Y: -2.0854718685150146
Z: 3.9860916137695312
Focal Shape Fixed Size: true
Focal Shape Size: 0.05000000074505806
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.009999999776482582
Pitch: 0.785398006439209
Pitch: 0.7503980398178101
Target Frame: <Fixed Frame>
Value: Orbit (rviz)
Yaw: 0.785398006439209
Yaw: 4.923583030700684
Saved: ~
Window Geometry:
Displays:
collapsed: false
Height: 846
Height: 1016
Hide Left Dock: false
Hide Right Dock: false
QMainWindow State: 000000ff00000000fd000000040000000000000156000002b4fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000002b4000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002b4fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003b000002b4000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b00000003efc0100000002fb0000000800540069006d00650100000000000004b00000025300fffffffb0000000800540069006d006501000000000000045000000000000000000000023f000002b400000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
QMainWindow State: 000000ff00000000fd0000000400000000000001560000035efc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b0000035e000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f0000035efc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003b0000035e000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073a0000003efc0100000002fb0000000800540069006d006501000000000000073a0000025300fffffffb0000000800540069006d00650100000000000004500000000000000000000004c90000035e00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Time:
Expand All @@ -128,6 +296,6 @@ Window Geometry:
collapsed: false
Views:
collapsed: false
Width: 1200
X: 72
Y: 60
Width: 1850
X: 70
Y: 27
Original file line number Diff line number Diff line change
@@ -0,0 +1,81 @@
import threading
import math
import rclpy
from rclpy.node import Node
from nav_msgs.msg import Odometry
from sensor_msgs.msg import JointState
from transforms3d.euler import quat2euler

class GimbalStabilizerNode(Node):
def __init__(self):
super().__init__('gimbal_stabilizer')

# Publisher to send joint commands
self.joint_pub = self.create_publisher(JointState, '/joint_command', 10)

# Subscriber to receive drone odometry
self.create_subscription(Odometry, '/robot_1/odometry_conversion/odometry', self.odometry_callback, 10)
self.create_subscription(JointState, '/joint_states', self.joint_callback, 10)

# Initialize joint state message
self.joint_command = JointState()
self.joint_command.name = ["yaw_joint","roll_joint", "pitch_joint"]
self.joint_command.position = [0.0, 0.0, 0.0]

def joint_callback(self, msg):
# Inverse the drone angles to stabilize the gimbal
# self.joint_command.position[0] = -roll # roll joint
# self.joint_command.position[1] = -pitch # pitch joint
# self.joint_command.position[2] = -yaw # yaw joint

# self.joint_command.effort = [100000000.0, 100000000.0, 100000000.0]

# self.joint_command.position[0] = -20.0/180*3.14 # yaw joint
# self.joint_command.position[1] = 10.0/180*3.14 # roll joint
# self.joint_command.position[2] = 20.0/180*3.14 # pitch joint
self.joint_command.velocity = [float('nan'), float('nan'), float('nan')]
# self.joint_command.velocity = [-1.0, -1.0, -1.0]

# Publish the joint command
# self.joint_pub.publish(self.joint_command)

def odometry_callback(self, msg):
# Extract quaternion from odometry message
orientation_q = msg.pose.pose.orientation
quaternion = [
orientation_q.w,
orientation_q.x,
orientation_q.y,
orientation_q.z
]

# Convert quaternion to Euler angles (roll, pitch, yaw)
roll, pitch, yaw = quat2euler(quaternion, axes='sxyz')

# Inverse the drone angles to stabilize the gimbal
# self.joint_command.position[0] = -roll # roll joint
# self.joint_command.position[1] = -pitch # pitch joint
# self.joint_command.position[2] = -yaw # yaw joint

self.joint_command.position[0] = -0.0/180*3.14 # yaw joint
self.joint_command.position[1] = -roll # roll joint
self.joint_command.position[2] = 0.0/180*3.14 # pitch joint
self.joint_command.velocity = [float('nan'), float('nan'), float('nan')]
self.joint_command.velocity = [-1.0, -1.0, -1.0]

# Publish the joint command
self.joint_pub.publish(self.joint_command)

def main():
rclpy.init()
node = GimbalStabilizerNode()

try:
rclpy.spin(node) # Run the node in a single thread
except KeyboardInterrupt:
pass
finally:
rclpy.shutdown()

if __name__ == '__main__':
main()
23 changes: 23 additions & 0 deletions robot/ros_ws/src/autonomy/1_sensors/gimbal_stabilizer/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>gimbal_stabilizer</name>
<version>0.0.0</version>
<description>TODO: Package description</description>
<maintainer email="caomuqing@163.com">airstation-04</maintainer>
<license>TODO: License declaration</license>

<depend>rclpy</depend>
<depend>nav_msgs</depend>
<depend>sensor_msgs</depend>
<depend>tf_transformations</depend>

<test_depend>ament_copyright</test_depend>
<test_depend>ament_flake8</test_depend>
<test_depend>ament_pep257</test_depend>
<test_depend>python3-pytest</test_depend>

<export>
<build_type>ament_python</build_type>
</export>
</package>
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
[develop]
script_dir=$base/lib/gimbal_stabilizer
[install]
install_scripts=$base/lib/gimbal_stabilizer
25 changes: 25 additions & 0 deletions robot/ros_ws/src/autonomy/1_sensors/gimbal_stabilizer/setup.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
from setuptools import find_packages, setup

package_name = 'gimbal_stabilizer'

setup(
name=package_name,
version='0.1.0',
packages=[package_name],
data_files=[
('share/ament_index/resource_index/packages', ['resource/' + package_name]),
('share/' + package_name, ['package.xml']),
],
install_requires=['setuptools'],
zip_safe=True,
maintainer='Your Name',
maintainer_email='you@example.com',
description='Package for gimbal stabilization using roll, pitch, and yaw from odometry data',
license='Apache License 2.0',
tests_require=['pytest'],
entry_points={
'console_scripts': [
'gimbal_stabilizer_node = gimbal_stabilizer.gimbal_stabilizer_node:main'
],
},
)
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
# Copyright 2015 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

from ament_copyright.main import main
import pytest


# Remove the `skip` decorator once the source file(s) have a copyright header
@pytest.mark.skip(reason='No copyright header has been placed in the generated source file.')
@pytest.mark.copyright
@pytest.mark.linter
def test_copyright():
rc = main(argv=['.', 'test'])
assert rc == 0, 'Found errors'
Loading