Skip to content

Commit

Permalink
fix galileo status to 30hz and refactor
Browse files Browse the repository at this point in the history
  • Loading branch information
xiaoqiang committed Dec 22, 2018
1 parent 1521516 commit 74727e7
Show file tree
Hide file tree
Showing 10 changed files with 484 additions and 385 deletions.
6 changes: 3 additions & 3 deletions monitor.py
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@
import rospy
from geometry_msgs.msg import Pose
from nav_msgs.msg import Odometry
from std_msgs.msg import Bool, Float64, UInt32
from std_msgs.msg import Bool, Float64, UInt32, Int32
from system_monitor.msg import Status
from xiaoqiang_log.msg import LogRecord

Expand Down Expand Up @@ -114,8 +114,8 @@ def monitor():
global REPORT_PUB
rospy.init_node("monitor", anonymous=True)
rospy.Subscriber("/usb_cam/brightness", UInt32, get_brightness)
rospy.Subscriber("/usb_cam/image_raw", rospy.AnyMsg, get_image)
rospy.Subscriber("/ORB_SLAM/Frame", rospy.AnyMsg, get_orb_start_status)
rospy.Subscriber("/usb_cam/camera_info", rospy.AnyMsg, get_image)
rospy.Subscriber("/ORB_SLAM/TrackingStatus", Int32, get_orb_start_status)
rospy.Subscriber("/xqserial_server/Power", Float64, get_power)
rospy.Subscriber("/xqserial_server/Odom", Odometry, get_odom)
rospy.Subscriber("/ORB_SLAM/Camera", Pose, get_orb_track_flag)
Expand Down
7 changes: 1 addition & 6 deletions orb_track.py
Original file line number Diff line number Diff line change
Expand Up @@ -145,12 +145,7 @@ def do_security():
# 视觉丢失超时保险
# 里程计丢失超时保险
if (CAMERA_UPDATE_FLAG and time2_diff.to_sec() > 180 and not BAR_FLAG) or time1_diff.to_sec() > 5.:
# 发布navFlag
if NAV_FLAG_PUB != None:
nav_flag = Bool()
nav_flag.data = True
NAV_FLAG_PUB.publish(nav_flag)
# 发布全局禁止flag
# 发布全局禁止flag
global_move_flag = Bool()
global_move_flag.data = False
GLOBAL_MOVE_PUB.publish(global_move_flag)
Expand Down
Loading

0 comments on commit 74727e7

Please sign in to comment.