Update local_mqtt_sub_data_from_ros.py

main
tony19990828 4 years ago committed by GitHub
parent 4c717a6cc7
commit 7c69228151
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23

@ -13,7 +13,7 @@ from sensor_msgs.msg import Imu
from sensor_msgs.msg import Range
from geometry_msgs.msg import Vector3
mqtt_config = {"host": "192.168.0.48", "port": 1883, "topic": "data/pub"}
mqtt_config = {"host": "192.168.100.157", "port": 1883, "topic": "data/pub"}
data ={}
# Ros
def callBack_imu(IMU):
@ -28,27 +28,30 @@ def callBack_imu(IMU):
dataImuUpdate = {"gyro_x": gyro_x, "gyro_y": gyro_y,"gyro_z":gyro_z, "accel_x": accel_x, "accel_y": accel_y, "accel_z": accel_z}
data.update(dataImuUpdate)
# print ('gyro_x:'+gyro_x+'\n'+'gyro_y:'+gyro_y+'\n'+'gyro_z:'+gyro_z +'\n')
# print ('accel_x:'+accel_x+'\n'+'accel_y:'+accel_y+'\n'+'accel_z:'+accel_z +'\n')
def callBack_gps(GPS):
lat=str(GPS.latitude)
lon=str(GPS.longitude)
dataGpsUpdate = {"lat": GPS.latitude, "lon": GPS.longitude}
data.update(dataGpsUpdate)
toJson(data)
# print ('lat:'+lat+'\n'+'lon:'+lon+'\n')
def callBack_rng(RNG):
dataRngUpdate = {"range": RNG.range}
data.update(dataRngUpdate)
dataJsonFormate = json.dumps(data)
# print ('range:'+range+'\n')
def toJson(data):
dataJsonFormate = json.dumps(data)
print (dataJsonFormate)
mqtt_Pub(message=dataJsonFormate)
# MQTT
def initialise_clients(clientname):
# callback assignment
@ -87,8 +90,7 @@ if __name__ == '__main__':
nodeName = 'save_data_py'
rospy.init_node(nodeName)
# topicName = 'data_topic'
subscriber = rospy.Subscriber('/mavros/imu/data_raw',Imu,callBack_imu) #從topic獲取string再呼叫callback
subscriber = rospy.Subscriber('/mavros/global_position/global',NavSatFix,callBack_gps) #從topic獲取string再呼叫callback
subscriber = rospy.Subscriber('/mavros/rangefinder/rangefinder',Range,callBack_rng) #從topic獲取string再呼叫callback
subscriber1 = rospy.Subscriber('/mavros/imu/data_raw',Imu,callBack_imu) #從topic獲取string再呼叫callback
subscriber2 = rospy.Subscriber('/mavros/global_position/global',NavSatFix,callBack_gps) #從topic獲取string再呼叫callback
subscriber3 = rospy.Subscriber('/mavros/rangefinder/rangefinder',Range,callBack_rng) #從topic獲取string再呼叫callback
rospy.spin()

Loading…
Cancel
Save