Skip to content

Files

Latest commit

14e99f9 · Apr 5, 2025

History

History
748 lines (497 loc) · 12.9 KB

python_api_documentation.md

File metadata and controls

748 lines (497 loc) · 12.9 KB

Python API Documentation

This document provides comprehensive documentation for the Python wrapper methods defined in python_api.cpp. The wrapper uses pybind11 to expose C++ functionality to Python.

Table of Contents

Module: pydsr

The main module for DSR API in Python.

import pydsr

Description

DSR Api for python - Provides access to the Distributed Scene Graph (DSR) functionality.

Submodule: signals

Connect functions to DSR signals. The types of the signals are defined in the signal_type enum.

Enumerations

signal_type

Enum values:

  • UPDATE_NODE
  • UPDATE_NODE_ATTR
  • UPDATE_EDGE
  • UPDATE_EDGE_ATTR
  • DELETE_EDGE
  • DELETE_NODE
  • DELETE_NODE_OBJ
  • DELETE_EDGE_OBJ

Methods

connect

signals.connect(graph, signal_type, callback_function)

Connect a callback function to a specific signal type.

Parameters:

  • graph: DSRGraph - The graph instance to connect to
  • signal_type: signal_type - The type of signal to connect to
  • callback_function: function - The callback function to be called when the signal is emitted

Function Signatures for Callbacks:

  • UPDATE_NODE: function(int, str) -> None
  • UPDATE_NODE_ATTR: function(int, [str]) -> None
  • UPDATE_EDGE: function(int, int, str) -> None
  • UPDATE_EDGE_ATTR: function(int, int, [str]) -> None
  • DELETE_EDGE: function(int, int, str) -> None
  • DELETE_NODE: function(int) -> None
  • DELETE_NODE_OBJ: function(pydsr.Node) -> None
  • DELETE_EDGE_OBJ: function(pydsr.Edge) -> None

Class: Attribute

Represents an attribute in the DSR system.

Constructors

Attribute(value, timestamp, agent_id)
Attribute(value, agent_id)
Attribute(value)

Parameters:

  • value: The value of the attribute (various types supported)
  • timestamp: uint64_t - Timestamp in nanoseconds (optional)
  • agent_id: uint32_t - ID of the agent (optional)

Properties

agent_id (read-only)

attribute.agent_id

Read the agent_id attribute. This property is readonly and is updated when a change is made in the value property.

timestamp (read-only)

attribute.timestamp

Read the timestamp (ns) attribute. This property is readonly and is updated when a change is made in the value property.

value (read-write)

attribute.value
attribute.value = new_value

Read or assign a new value to the Attribute object.

Methods

repr

repr(attribute)

Returns a string representation of the attribute.

Class: Edge

Represents an edge in the DSR graph.

Constructors

Edge(to, from, type, agent_id)

Parameters:

  • to: uint64_t - Destination node ID
  • from: uint64_t - Origin node ID
  • type: str - Type of the edge
  • agent_id: uint32_t - ID of the agent

Properties

type (read-only)

edge.type

Read the type of the edge. This property is readonly.

origin (read-only)

edge.origin

Read the origin node of the edge. This property is readonly.

destination (read-only)

edge.destination

Read the destination node of the edge. This property is readonly.

agent_id (read-write)

edge.agent_id
edge.agent_id = new_agent_id

Read or assign a new value to the agent_id attribute.

attrs (read-write)

edge.attrs
edge.attrs = new_attrs

Read or write in the attribute map of the edge.

Methods

repr

repr(edge)

Returns a string representation of the edge.

Class: Node

Represents a node in the DSR graph.

Constructors

Node(agent_id, type, name="")

Parameters:

  • agent_id: uint32_t - ID of the agent
  • type: str - Type of the node
  • name: str - Name of the node (optional, default="")

Properties

id (read-only)

node.id

Read the id of the node. This property is readonly and is generated by the idserver agent when the node is inserted.

name (read-only)

node.name

Read the name of the node. This property is readonly. If the name is not provided to the constructor or the name already exists in G, the name is generated by the idserver agent with a combination of the type and the id when the node is inserted.

type (read-only)

node.type

Read the type of the node. This property is readonly.

agent_id (read-write)

node.agent_id
node.agent_id = new_agent_id

Read or assign a new value to the agent_id attribute.

attrs (read-write)

node.attrs
node.attrs = new_attrs

Read or write in the attribute map of the node.

edges (read-write)

node.edges
node.edges = new_edges

Read or write in the edge map of the node.

Methods

repr

repr(node)

Returns a string representation of the node.

get_edges

node.get_edges()

Returns a list of all edges connected to the node.

Returns:

  • List of Edge objects

Class: DSRGraph

Represents the Distributed Scene Graph.

Constructors

DSRGraph(root, name, id, dsr_input_file="", all_same_host=True)

Parameters:

  • root: int - Root node ID
  • name: str - Name of the graph
  • id: int - ID of the agent
  • dsr_input_file: str - Input file path (optional, default="")
  • all_same_host: bool - Whether all agents are on the same host (optional, default=True)

Methods

get_agent_id

graph.get_agent_id()

Get the agent ID.

Returns:

  • uint32_t - Agent ID

get_agent_name

graph.get_agent_name()

Get the agent name.

Returns:

  • str - Agent name

get_node

graph.get_node(id)
graph.get_node(name)

Return the node with the id or name passed as parameter.

Parameters:

  • id: uint64_t - ID of the node
  • name: str - Name of the node

Returns:

  • Node or None - Returns None if the node does not exist

delete_node

graph.delete_node(id)
graph.delete_node(name)

Delete the node with the given id or name.

Parameters:

  • id: uint64_t - ID of the node
  • name: str - Name of the node

Returns:

  • bool - Result of the operation

insert_node

graph.insert_node(node)

Insert a new node in the graph.

Parameters:

  • node: Node - Node to insert

Returns:

  • uint64_t or None - ID of the node or None if the Node already exists in the map

update_node

graph.update_node(node)

Update the node in the graph.

Parameters:

  • node: Node - Node to update

Returns:

  • bool - Result of the operation

get_edge

graph.get_edge(from, to, type)

Return the edge with the parameters from, to, and type.

Parameters:

  • from: uint64_t or str - Origin node ID or name
  • to: uint64_t or str - Destination node ID or name
  • type: str - Type of the edge

Returns:

  • Edge or None - Returns None if the edge does not exist

insert_or_assign_edge

graph.insert_or_assign_edge(edge)

Insert or update an edge.

Parameters:

  • edge: Edge - Edge to insert or update

Returns:

  • bool - Result of the operation

delete_edge

graph.delete_edge(from, to, type)

Remove an edge.

Parameters:

  • from: uint64_t or str - Origin node ID or name
  • to: uint64_t or str - Destination node ID or name
  • type: str - Type of the edge

Returns:

  • bool - Result of the operation

get_node_root

graph.get_node_root()

Return the root node.

Returns:

  • Node - Root node

get_nodes_by_type

graph.get_nodes_by_type(type)

Return all the nodes with a given type.

Parameters:

  • type: str - Type of the nodes

Returns:

  • List of Node objects

get_nodes

graph.get_nodes()

Returns all nodes in the graph.

Returns:

  • List of Node objects

get_name_from_id

graph.get_name_from_id(id)

Return the name of a node given its id.

Parameters:

  • id: uint64_t - ID of the node

Returns:

  • str - Name of the node

get_id_from_name

graph.get_id_from_name(name)

Return the id from a node given its name.

Parameters:

  • name: str - Name of the node

Returns:

  • uint64_t - ID of the node

get_edges

graph.get_edges()

Return all the edges in the graph.

Returns:

  • List of Edge objects

get_edges_by_type

graph.get_edges_by_type(type)

Return all the edges with a given type.

Parameters:

  • type: str - Type of the edges

Returns:

  • List of Edge objects

get_edges_to_id

graph.get_edges_to_id(id)

Return all the edges that point to the node.

Parameters:

  • id: uint64_t - ID of the node

Returns:

  • List of Edge objects

write_to_json_file

graph.write_to_json_file(file, skip_atts=[])

Write the graph to a JSON file.

Parameters:

  • file: str - Path to the output file
  • skip_atts: List[str] - List of attributes to skip (optional, default=[])

Class: rt_api

Real-time API for the DSR graph.

Constructors

rt_api(graph)

Parameters:

  • graph: DSRGraph - The graph instance

Methods

insert_or_assign_edge_RT

rt.insert_or_assign_edge_RT(node, to, trans, rot_euler)

Insert or assign an RT edge.

Parameters:

  • node: Node - Origin node
  • to: uint64_t - Destination node ID
  • trans: List[float] - Translation vector
  • rot_euler: List[float] - Rotation in Euler angles

get_edge_RT (static)

rt_api.get_edge_RT(node, to)

Get an RT edge.

Parameters:

  • node: Node - Origin node
  • to: uint64_t - Destination node ID

Returns:

  • Edge or None

get_RT_pose_from_parent

rt.get_RT_pose_from_parent(node)

Get the RT pose from the parent node.

Parameters:

  • node: Node - Node to get the pose from

Returns:

  • 4x4 transformation matrix or None

get_edge_RT_as_rtmat

rt.get_edge_RT_as_rtmat(edge, timestamp=0)

Get the RT edge as a transformation matrix.

Parameters:

  • edge: Edge - Edge to get the transformation from
  • timestamp: uint64_t - Timestamp (optional, default=0)

Returns:

  • 4x4 transformation matrix or None

get_translation

rt.get_translation(node_id, to, timestamp=0)

Get the translation vector.

Parameters:

  • node_id: uint64_t - Origin node ID
  • to: uint64_t - Destination node ID
  • timestamp: uint64_t - Timestamp (optional, default=0)

Returns:

  • 3D vector or None

Class: inner_api

Inner Eigen API for the DSR graph.

Constructors

inner_api(graph)

Parameters:

  • graph: DSRGraph - The graph instance

Methods

transform

inner.transform(orig, dest, timestamp=0)
inner.transform(orig, vector, dest, timestamp=0)

Transform a point or vector from one frame to another.

Parameters:

  • orig: str - Origin frame
  • dest: str - Destination frame
  • vector: 3D vector - Vector to transform (optional)
  • timestamp: uint64_t - Timestamp (optional, default=0)

Returns:

  • 3D vector or None

transform_axis

inner.transform_axis(orig, dest, timestamp=0)
inner.transform_axis(orig, vector, dest, timestamp=0)

Transform an axis from one frame to another.

Parameters:

  • orig: str - Origin frame
  • dest: str - Destination frame
  • vector: 6D vector - Vector to transform (optional)
  • timestamp: uint64_t - Timestamp (optional, default=0)

Returns:

  • 6D vector or None

get_transformation_matrix

inner.get_transformation_matrix(orig, dest, timestamp=0)

Get the transformation matrix between two frames.

Parameters:

  • orig: str - Origin frame
  • dest: str - Destination frame
  • timestamp: uint64_t - Timestamp (optional, default=0)

Returns:

  • 4x4 transformation matrix or None

get_rotation_matrix

inner.get_rotation_matrix(orig, dest, timestamp=0)

Get the rotation matrix between two frames.

Parameters:

  • orig: str - Origin frame
  • dest: str - Destination frame
  • timestamp: uint64_t - Timestamp (optional, default=0)

Returns:

  • 3x3 rotation matrix or None

get_translation_vector

inner.get_translation_vector(orig, dest, timestamp=0)

Get the translation vector between two frames.

Parameters:

  • orig: str - Origin frame
  • dest: str - Destination frame
  • timestamp: uint64_t - Timestamp (optional, default=0)

Returns:

  • 3D vector or None

get_euler_xyz_angles

inner.get_euler_xyz_angles(orig, dest, timestamp=0)

Get the Euler angles (XYZ) between two frames.

Parameters:

  • orig: str - Origin frame
  • dest: str - Destination frame
  • timestamp: uint64_t - Timestamp (optional, default=0)

Returns:

  • 3D vector (Euler angles) or None