ROS2 Basics in 5 Days: Course Project: Rosject Section 3: 'ActionServer' object has no attribute '_handle'

I’m attempting to build the action server for section 3 of the Rosject for ROS2 Basics in 5 Days: Course Project. I’ve successfully built the packages after changing around the OdomRecord.action file.

Documentation shows:

​
---
geometry_msgs/msg/Point[] list_of_odoms
---
float32 current_total

This caused problems during the build. A search of the forums shows this as a solution:

OdomRecord.action

---
geometry_msgs/Point[] list_of_odoms
---
float32 current_total

I created a launch file just for the action server to make sure everything with the server was ok. When launching the action server I get this error:

user:~/ros2_ws$ ros2 launch wall_follower action.launch.py
[INFO] [launch]: All log files can be found below /home/user/.ros/log/2024-03-04-23-03-03-892993-1_xterm-5391
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [odom_recorder-1]: process started with pid [5393]
[odom_recorder-1] Traceback (most recent call last):
[odom_recorder-1]   File "/opt/ros/foxy/lib/python3.8/site-packages/rosidl_generator_py/import_type_support_impl.py", line 46, in import_type_support
[odom_recorder-1]     return importlib.import_module(module_name, package=pkg_name)
[odom_recorder-1]   File "/usr/lib/python3.8/importlib/__init__.py", line 127, in import_module
[odom_recorder-1]     return _bootstrap._gcd_import(name[level:], package, level)
[odom_recorder-1]   File "<frozen importlib._bootstrap>", line 1014, in _gcd_import
[odom_recorder-1]   File "<frozen importlib._bootstrap>", line 991, in _find_and_load
[odom_recorder-1]   File "<frozen importlib._bootstrap>", line 975, in _find_and_load_unlocked
[odom_recorder-1]   File "<frozen importlib._bootstrap>", line 657, in _load_unlocked
[odom_recorder-1]   File "<frozen importlib._bootstrap>", line 556, in module_from_spec
[odom_recorder-1]   File "<frozen importlib._bootstrap_external>", line 1166, in create_module
[odom_recorder-1]   File "<frozen importlib._bootstrap>", line 219, in _call_with_frames_removed
[odom_recorder-1] ImportError: /home/user/ros2_ws/install/odom_interface/lib/libodom_interface__rosidl_generator_c.so: undefined symbol: geometry_msgs__msg__Point__Sequence__init
[odom_recorder-1]
[odom_recorder-1] During handling of the above exception, another exception occurred:
[odom_recorder-1]
[odom_recorder-1] Traceback (most recent call last):
[odom_recorder-1]   File "/home/user/ros2_ws/install/wall_follower/lib/wall_follower/odom_recorder", line 33, in <module>
[odom_recorder-1]     sys.exit(load_entry_point('wall-follower==0.0.0', 'console_scripts', 'odom_recorder')())
[odom_recorder-1]   File "/home/user/ros2_ws/install/wall_follower/lib/python3.8/site-packages/wall_follower/odom_recorder.py", line 92, in main
[odom_recorder-1]     odom_action_server = OdomActionServer()
[odom_recorder-1]   File "/home/user/ros2_ws/install/wall_follower/lib/python3.8/site-packages/wall_follower/odom_recorder.py", line 17, in __init__
[odom_recorder-1]     self._action_server = ActionServer(self, OdomRecord, 'record_odom', self.execute_callback)
[odom_recorder-1]   File "/opt/ros/foxy/lib/python3.8/site-packages/rclpy/action/server.py", line 249, in __init__
[odom_recorder-1]     check_for_type_support(action_type)
[odom_recorder-1]   File "/opt/ros/foxy/lib/python3.8/site-packages/rclpy/type_support.py", line 29, in check_for_type_support
[odom_recorder-1]     msg_type.__class__.__import_type_support__()
[odom_recorder-1]   File "/home/user/ros2_ws/install/odom_interface/lib/python3.8/site-packages/odom_interface/action/_odom_record.py", line 1162, in __import_type_support__
[odom_recorder-1]     module = import_type_support('odom_interface')
[odom_recorder-1]   File "/opt/ros/foxy/lib/python3.8/site-packages/rosidl_generator_py/import_type_support_impl.py", line 48, in import_type_support
[odom_recorder-1]     raise UnsupportedTypeSupport(pkg_name)
[odom_recorder-1] rosidl_generator_py.import_type_support_impl.UnsupportedTypeSupport: Could not import 'rosidl_typesupport_c' for package 'odom_interface'
[odom_recorder-1] Exception ignored in: <function ActionServer.__del__ at 0x7f0ab951e790>
[odom_recorder-1] Traceback (most recent call last):
[odom_recorder-1]   File "/opt/ros/foxy/lib/python3.8/site-packages/rclpy/action/server.py", line 633, in __del__
[odom_recorder-1]     self.destroy()
[odom_recorder-1]   File "/opt/ros/foxy/lib/python3.8/site-packages/rclpy/action/server.py", line 620, in destroy
[odom_recorder-1]     if self._handle is None:
[odom_recorder-1] AttributeError: 'ActionServer' object has no attribute '_handle'
[ERROR] [odom_recorder-1]: process has died [pid 5393, exit code 1, cmd '/home/user/ros2_ws/install/wall_follower/lib/wall_follower/odom_recorder --ros-args'].

I have created a custom interface called odom_interface.
CMakeLists.txt:

cmake_minimum_required(VERSION 3.5)
project(odom_interface)

# Default to C99
if(NOT CMAKE_C_STANDARD)
  set(CMAKE_C_STANDARD 99)
endif()

# Default to C++14
if(NOT CMAKE_CXX_STANDARD)
  set(CMAKE_CXX_STANDARD 14)
endif()

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
  add_compile_options(-Wall -Wextra -Wpedantic)
endif()

# find dependencies
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)
find_package(action_msgs REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(rosidl_default_generators REQUIRED)

if(BUILD_TESTING)
  find_package(ament_lint_auto REQUIRED)
  ament_lint_auto_find_test_dependencies()
endif()

rosidl_generate_interfaces(${PROJECT_NAME}
  "action/OdomRecord.action"
)

ament_package()

package.xml:

<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
  <name>odom_interface</name>
  <version>0.0.0</version>
  <description>TODO: Package description</description>
  <maintainer email="user@todo.todo">user</maintainer>
  <license>TODO: License declaration</license>

  <buildtool_depend>ament_cmake</buildtool_depend>

  <depend>rclcpp</depend>
  <depend>std_msgs</depend>
  <depend>action_msgs</depend>
  <depend>geometry_msgs</depend>

  <build_depend>rosidl_default_generators</build_depend>
  <exec_depend>rosidl_default_runtime</exec_depend>
  <member_of_group>rosidl_interface_packages</member_of_group>

  <test_depend>ament_lint_auto</test_depend>
  <test_depend>ament_lint_common</test_depend>

  <export>
    <build_type>ament_cmake</build_type>
  </export>
</package>

odom_recorder.py:

import rclpy
from rclpy.action import ActionServer
from rclpy.node import Node
from rclpy.qos import ReliabilityPolicy, QoSProfile
from odom_interface.action import OdomRecord
from nav_msgs.msg import Odometry
from geometry_msgs.msg import Point32
from geometry_msgs.msg import Point
from std_msgs.msg import Float64
import time
from rclpy.executors import MultiThreadedExecutor

class OdomActionServer(Node):

    def __init__(self):
        super().__init__('odom_action_server')
        self._action_server = ActionServer(self, OdomRecord, 'record_odom', self.execute_callback)
        self.distance_publisher = self.create_publisher(Float64, 'total_distance', 10)
        self.subscriber = self.create_subscription(Odometry, '/odom', self.odom_callback, QoSProfile(depth=10, reliability=ReliabilityPolicy.RELIABLE))
        
        self.execute_goal = False
        self.stored_init_meas = False
        
        self.first_odom = Point32()
        self.last_odom = Point32()
        self.odom_record = []
        
        self.total_distance = 0.0
        self.last_x = 0.0
        self.last_y = 0.0 

    def odom_callback(self, msg):
        if self.execute_goal:
            self.last_odom.x = msg.pose.pose.position.x
            self.last_odom.y = msg.pose.pose.position.y
            self.last_odom.z = msg.pose.pose.orientation.z

            if not self.stored_init_meas:
                self.first_odom.x = self.last_odom.x
                self.first_odom.y = self.last_odom.y
                self.first_odom.z = self.last_odom.z
                self.get_logger().info(f'Initial measurement: {self.first_odom}')
                self.odom_record.append(Point(x=self.first_odom.x, y=self.first_odom.y, z=0))  # Append the first_odom to the record
                self.stored_init_meas = True

            self.odom_record.append(Point(x=self.last_odom.x, y=self.last_odom.y, z=0))  # Append the current last_odom to the record

            # Check if the robot has returned to the initial position
            dist_to_start = ((self.last_odom.x - self.first_odom.x) ** 2 + (self.last_odom.y - self.first_odom.y) ** 2) ** 0.5
            if dist_to_start < 0.05:  # 5 cm
                self.get_logger().info('Robot has returned to the initial position.')
                self.execute_goal = False
                self.stored_init_meas = False
                self.set_result()

    def execute_callback(self, goal_handle):
        self.get_logger().info('Executing goal...')
        self.execute_goal = True
        self.total_distance = 0.0
        self.first_odom.x = 0.0
        self.first_odom.y = 0.0
        self.first_odom.z = 0.0
        self.last_odom.x = 0.0
        self.last_odom.y = 0.0
        self.last_odom.z = 0.0
        self.odom_record = []  # Reset the odom_record list

        # Create a timer to periodically publish feedback
        self.timer = self.create_timer(1.0, lambda: self.publish_feedback(goal_handle))

    def publish_feedback(self, goal_handle):
        if len(self.odom_record) >= 2:
            self.last_x = self.odom_record[-2].x
            self.last_y = self.odom_record[-2].y
            dist_p1_p2 = ((self.last_odom.x - self.last_x) ** 2 + (self.last_odom.y - self.last_y) ** 2) ** 0.5
            self.total_distance += dist_p1_p2

        feedback_msg = OdomRecord.Feedback()
        feedback_msg.current_total = self.total_distance
        goal_handle.publish_feedback(feedback_msg)
        
        self.distance_publisher.publish(Float64(data=self.total_distance))

    def set_result(self):
        result = OdomRecord.Result()
        result.list_of_odoms = self.odom_record
        self._action_server.set_succeeded(result)
        self.get_logger().info('Action succeeded. Total distance traveled: {0}'.format(self.total_distance))

def main(args=None):
    rclpy.init(args=args)
    odom_action_server = OdomActionServer()
    # Create a MultiThreadedExecutor
    executor = MultiThreadedExecutor(num_threads=4)
    # adding node to executor
    executor.add_node(odom_action_server)
    try:
        # spin the executor
        executor.spin()
    finally:
        executor.shutdown()
        odom_action_server.destroy_node()
    rclpy.shutdown()

if __name__ == '__main__':
    main

Could someone give me some guidance on how to address this error?

Thank you.

Hi @pharva ,

This is commonly referred to as type_support error in ROS2.
This error is usually related to rosidl_generator in the CMakeLists.txt file.
Although the error report looks quite long and not-so-easy to understand, it is much easy to understand on the contrary.

This is the most important line that gives you the hint.
It says geometry_msgs/msg/Point array is undefined.
undefined symbol: geometry_msgs__msg__Point__Sequence__init
This error comes from libodom_interface__rosidl_generator_c.so, which is related to the rosidl_generate_interfaces(...) code-block in the CMakeLists.txt file.

Now you have narrowed down what the issue is.

Your solution is very simple:
If you have not added geometry_msgs as a package dependency, you add it.

Looking at your CMakeLists.txt file, it seems that you have added the dependency. But why do you still get this error?
This is because, the following function, rosidl_generate_interfaces(...) also needs to know which dependencies are required for custom interface generation.

So the next part of the solution is to add the dependency into the above function, like so:

rosidl_generate_interfaces(${PROJECT_NAME}
  "action/OdomRecord.action"
  DEPENDENCIES std_msgs geometry_msgs   # <--- add this line
)

I usually make it a habit to add std_msgs also into DEPENDENCIES if I am using std_msgs also as one of my dependencies for my package. Why? Because std_msgs are the basic type of messages onto which other message types are built on.

I hope I have explained you how to debug these kind of issues, as well as solved your issue.

Let me know if you still have any issues.

Regards,
Girish

@girishkumar.kannan That did it! Thank you. I didn’t know that the dependencies were needed within rosidl_generate_interfaces .

Hi @pharva ,

Glad to know that your issue is now fixed.

Please mark this issue as solved (by marking the appropriate post as the solution), so this thread can be closed.

Regards,
Girish

This topic was automatically closed 10 days after the last reply. New replies are no longer allowed.