Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

TypeError: can't pickle _thread.lock objects #77

Open
ML-S opened this issue Sep 25, 2020 · 0 comments
Open

TypeError: can't pickle _thread.lock objects #77

ML-S opened this issue Sep 25, 2020 · 0 comments

Comments

@ML-S
Copy link

ML-S commented Sep 25, 2020

I run into a 'TypeError: can't pickle _thread.lock objects' - error when trying to execute my state machine.
The state-machine consists of a state that executes a command via subprocess.popen and stores the process in a userdata-variable followed by a concurrent container with random content.
When running the code, it throws the following error:

[INFO] [1601065188.496524]: State machine starting in initial state 'ST1' with userdata: 
	['process']
[INFO] [1601065188.501100]: State machine transitioning 'ST1':'succeeded'-->'CON_SUB'
[ERROR] [1601065188.503611]: Could not execute transition callback: Traceback (most recent call last):
  File "/home/faps/catkin_ws/src/executive_smach/smach/src/smach/container.py", line 175, in call_transition_cbs
    cb(self.userdata, self.get_active_states(), *args)
  File "/home/faps/catkin_ws/src/executive_smach/smach_ros/src/smach_ros/introspection.py", line 239, in _transition_cb
    self._publish_status(info_str)
  File "/home/faps/catkin_ws/src/executive_smach/smach_ros/src/smach_ros/introspection.py", line 226, in _publish_status
    base64.b64encode(pickle.dumps(self._container.userdata._data, 2)).decode('utf-8'),
TypeError: can't pickle _thread.lock objects

[INFO] [1601065188.504891]: Concurrence starting with userdata: 
	[]
[INFO] [1601065188.506516]: Concurrent state 'ST2' returned outcome 'succeeded' on termination.
[INFO] [1601065188.508192]: Concurrent Outcomes: {'ST2': 'succeeded'}
[INFO] [1601065188.509342]: State machine terminating 'CON_SUB':'succeeded':'succeeded'
exit-outcome:succeeded

I've tried out a few things and made the following observations:

  • The error only appears when using the smach_ros.IntrospectionServer, without it it runs perfectly fine (you can see that the code runs through and returns succeeded nevertheless)
  • The error doesn't appear when I outcomment the subprocess.Popen
  • The error doesn't appear when I don't store the process in the userdata (for example by outcommenting the line userdata.out_proc = process)
  • The error doesn't appear when ST1 transitions to another simple state ST2 without the concurrence-container (maybe due to the transition-callback like mentioned in the error?)

For you to reproduce, the corresponding code looks as follows:

#!/usr/bin/env python3

import smach
import smach_ros
import subprocess
import rospy
import os


# gets called when ANY child state terminates
def con_term_cb(outcome_map):
    # terminate all running states if SM_1 finished with outcome 'goal_reached'
    if outcome_map['ST2'] == 'succeeded':
        return True
    # terminate all running states if SM_1 finished with outcome 'preempted'
    if outcome_map['ST2'] == 'preempted':
        return True
    # in all other case, just keep running, don't terminate anything
    return False


# gets called when ALL child states are terminated
def con_out_cb(outcome_map):
   if outcome_map['ST2'] == 'succeeded':
      return 'succeeded'
   elif outcome_map['ST2'] == 'preempted':
      return 'preempted'

class st1(smach.State):
    def __init__(self, outcomes=['succeeded', 'preempted']):
        smach.State.__init__(self, outcomes, input_keys=['in_proc'], output_keys=['out_proc'])

    def execute(self, userdata):
        if self.preempt_requested():
            self.service_preempt()
            return 'preempted'

        process = subprocess.Popen('rosbag play -l /home/faps/bags/2020-05-07-11-10-22.bag', stdout=subprocess.PIPE,
                                   shell=True, preexec_fn=os.setsid)
        userdata.out_proc = process
        return 'succeeded'


class st2(smach.State):
    def __init__(self, outcomes=['succeeded', 'preempted']):
        smach.State.__init__(self, outcomes)

    def execute(self, userdata):
        # time.sleep(2)
        if self.preempt_requested():
            self.service_preempt()
            return 'preempted'
        return 'succeeded'


if __name__ == "__main__":
    rospy.init_node('test_state_machine')
    sm_1 = smach.StateMachine(outcomes=['succeeded', 'preempted'])
    sm_1.userdata.process = None
    with sm_1:
        con_sub1 = smach.Concurrence(outcomes=['succeeded', 'preempted'],
                                     default_outcome='preempted',
                                     child_termination_cb=con_term_cb,
                                     outcome_cb=con_out_cb
                                     )

        with con_sub1:
            smach.Concurrence.add('ST2', st2())

        smach.StateMachine.add('ST1', st1(),
                               transitions={'succeeded': 'CON_SUB', 'preempted': 'CON_SUB'},
                               remapping={'out_proc': 'process'})
        smach.StateMachine.add('CON_SUB', con_sub1, transitions={'succeeded': 'succeeded', 'preempted': 'preempted'})

    # Execute SMACH plan
    # Create and start the introspection server
    sis = smach_ros.IntrospectionServer('introspection_server', sm_1, '/SM_ROOT')
    sis.start()
    outcome = sm_1.execute()
    print('exit-outcome:' + outcome)
    # Wait for ctrl-c to stop the application
    rospy.spin()
    sis.stop()
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

1 participant