mirror of
https://github.com/bjoernellens1/rmp220_middleware.git
synced 2025-01-19 00:16:59 +00:00
Update rmp220_middleware.py fix node attributes
This commit is contained in:
parent
7155eb3449
commit
90a6d1d9f9
@ -34,54 +34,50 @@ class StateMachineNode:
|
|||||||
self.joy_sub = rospy.Subscriber('/joy', Joy, self.joy_callback)
|
self.joy_sub = rospy.Subscriber('/joy', Joy, self.joy_callback)
|
||||||
self.chassis_mode_sub = rospy.Subscriber('/chassis_mode_fb', ChassisModeFb, self.chassis_mode_callback)
|
self.chassis_mode_sub = rospy.Subscriber('/chassis_mode_fb', ChassisModeFb, self.chassis_mode_callback)
|
||||||
|
|
||||||
# Service clients
|
# Service client initialization with a check
|
||||||
rospy.wait_for_service('set_chassis_enable')
|
try:
|
||||||
|
rospy.wait_for_service('set_chassis_enable', timeout=5)
|
||||||
self.chassis_enable_client = rospy.ServiceProxy('set_chassis_enable', RosSetChassisEnableCmd)
|
self.chassis_enable_client = rospy.ServiceProxy('set_chassis_enable', RosSetChassisEnableCmd)
|
||||||
rospy.loginfo('Chassis enable service available.')
|
rospy.loginfo('Chassis enable service available.')
|
||||||
|
except rospy.ROSException as e:
|
||||||
|
rospy.logerr(f"Failed to wait for 'set_chassis_enable' service: {e}")
|
||||||
|
self.chassis_enable_client = None
|
||||||
|
|
||||||
# Timer for periodic updates
|
# Timer for periodic updates
|
||||||
self.timer = rospy.Timer(rospy.Duration(0.01), self.timer_callback) # 100 Hz
|
self.timer = rospy.Timer(rospy.Duration(0.01), self.timer_callback) # 100 Hz
|
||||||
|
|
||||||
def chassis_mode_callback(self, msg):
|
|
||||||
if self.state == State.PAUSED:
|
|
||||||
return
|
|
||||||
|
|
||||||
if msg.chassis_mode == 0:
|
|
||||||
self.state = State.DISABLED
|
|
||||||
rospy.loginfo('Set chassis_mode to DISABLED')
|
|
||||||
elif msg.chassis_mode == 1:
|
|
||||||
self.state = State.ENABLED
|
|
||||||
rospy.loginfo('Set chassis_mode to ENABLED')
|
|
||||||
elif msg.chassis_mode == 2:
|
|
||||||
self.state = State.PASSIVE
|
|
||||||
rospy.loginfo('Set chassis_mode to PASSIVE')
|
|
||||||
elif msg.chassis_mode == 3:
|
|
||||||
self.state = State.STOPPED
|
|
||||||
rospy.loginfo('Set chassis_mode to STOPPED')
|
|
||||||
|
|
||||||
def enable_chassis(self):
|
def enable_chassis(self):
|
||||||
|
if self.chassis_enable_client:
|
||||||
try:
|
try:
|
||||||
self.chassis_enable_client(True)
|
self.chassis_enable_client(True)
|
||||||
self.state = State.ENABLED
|
self.state = State.ENABLED
|
||||||
rospy.loginfo('Enabling chassis...')
|
rospy.loginfo('Enabling chassis...')
|
||||||
except rospy.ServiceException as e:
|
except rospy.ServiceException as e:
|
||||||
rospy.logerr(f'Failed to enable chassis: {e}')
|
rospy.logerr(f'Failed to enable chassis: {e}')
|
||||||
|
else:
|
||||||
|
rospy.logerr('Chassis enable client not initialized!')
|
||||||
|
|
||||||
def pause_chassis(self):
|
def pause_chassis(self):
|
||||||
|
if self.chassis_enable_client:
|
||||||
try:
|
try:
|
||||||
self.chassis_enable_client(False)
|
self.chassis_enable_client(False)
|
||||||
self.state = State.PAUSED
|
self.state = State.PAUSED
|
||||||
rospy.loginfo('Pausing chassis...')
|
rospy.loginfo('Pausing chassis...')
|
||||||
except rospy.ServiceException as e:
|
except rospy.ServiceException as e:
|
||||||
rospy.logerr(f'Failed to pause chassis: {e}')
|
rospy.logerr(f'Failed to pause chassis: {e}')
|
||||||
|
else:
|
||||||
|
rospy.logerr('Chassis enable client not initialized!')
|
||||||
|
|
||||||
def disable_chassis(self):
|
def disable_chassis(self):
|
||||||
|
if self.chassis_enable_client:
|
||||||
try:
|
try:
|
||||||
self.chassis_enable_client(False)
|
self.chassis_enable_client(False)
|
||||||
self.state = State.DISABLED
|
self.state = State.DISABLED
|
||||||
rospy.loginfo('Disabling chassis...')
|
rospy.loginfo('Disabling chassis...')
|
||||||
except rospy.ServiceException as e:
|
except rospy.ServiceException as e:
|
||||||
rospy.logerr(f'Failed to disable chassis: {e}')
|
rospy.logerr(f'Failed to disable chassis: {e}')
|
||||||
|
else:
|
||||||
|
rospy.logerr('Chassis enable client not initialized!')
|
||||||
|
|
||||||
def joy_callback(self, msg):
|
def joy_callback(self, msg):
|
||||||
start_button = msg.buttons[7] # Joystick button 'start'
|
start_button = msg.buttons[7] # Joystick button 'start'
|
||||||
|
Loading…
Reference in New Issue
Block a user