Skip to content

Commit

Permalink
Merge pull request #19 from sonia-auv/develop
Browse files Browse the repository at this point in the history
Develop
  • Loading branch information
supertoto29 authored Jun 27, 2022
2 parents 2cd6ca9 + d9453aa commit 62db0d5
Show file tree
Hide file tree
Showing 4 changed files with 40 additions and 3 deletions.
3 changes: 2 additions & 1 deletion .vscode/settings.json
Original file line number Diff line number Diff line change
Expand Up @@ -85,5 +85,6 @@
"python.analysis.extraPaths": [
"/home/sonia/base_lib_ws/devel/lib/python2.7/dist-packages",
"/opt/ros/melodic/lib/python2.7/dist-packages"
]
],
"ros.distro": "noetic"
}
3 changes: 3 additions & 0 deletions launch/provider_imu_simulation.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
<launch>
<node name="provider_imu" pkg="provider_imu" type="provider_imu_sim.py" output="screen" />
</launch>
6 changes: 4 additions & 2 deletions package.xml
Original file line number Diff line number Diff line change
@@ -1,12 +1,14 @@
<?xml version="1.0"?>
<package>
<name>provider_imu</name>
<version>1.2.3</version>
<version>1.2.4</version>
<description>The provider_imu package </description>

<author>Thibaut Mattio</author>
<author>Lucas Mongrain</author>
<author>Francis Alonzo</author>

<maintainer email="thibaut.mattio@gmail.com">Thibaut Mattio</maintainer>
<maintainer email="log.club.sonia@etsmtl.net">Software Team Leader</maintainer>

<license>GPLv3</license>

Expand Down
31 changes: 31 additions & 0 deletions src/provider_imu_sim.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,31 @@
#!/usr/bin/env python3
import rospy
import numpy
import struct
import os

from sonia_common.msg import *
from sensor_msgs.msg import *

def sim_imu():
rospy.init_node('provider_imu_simulation', anonymous=True)
pub = rospy.Publisher('/provider_imu/imu_info', Imu, queue_size=100)
rate = rospy.Rate(1) # 10hz
msg = Imu()
while not rospy.is_shutdown():

msg.linear_acceleration.x = numpy.random.uniform(0, 1)
msg.linear_acceleration.y = numpy.random.uniform(0, 1)
msg.linear_acceleration.z = numpy.random.uniform(0, 1)
pub.publish(msg)

rate.sleep()

if __name__ == '__main__':
try:
auv = os.getenv('LOCAL_AUV',"AUV7")
print("LOCAL_AUV set on : " + auv)
sim_imu()
except rospy.ROSInterruptException:
pass

0 comments on commit 62db0d5

Please sign in to comment.