Modules in irsl_choreonoid_ros

https://github.com/IRSL-tut/irsl_choreonoid_ros

irsl_choreonoid_ros.cnoid_ros_util

https://github.com/IRSL-tut/irsl_choreonoid_ros/blob/main/irsl_choreonoid_ros/cnoid_ros_util.py

irsl_choreonoid_ros.cnoid_ros_util.parseURLROS()

Refere parseURL in irsl_choreonoid.cnoid_util

Parameters:

url (str) – url

Returns:

Absolute path

Return type:

str

Examples

>>> parseURLROS('package://ros_package_name/dir/file')
/catkin_ws/install/share/ros_package_name/dir/file
irsl_choreonoid_ros.cnoid_ros_util.initializeROS(node_name=None, MASTER_URI=None, MASTER=None, MASTER_PORT=11311, IP=None, HOSTNAME=None, **kwargs)

irsl_choreonoid_ros.camera_utils

https://github.com/IRSL-tut/irsl_choreonoid_ros/blob/main/irsl_choreonoid_ros/camera_utils.py

class irsl_choreonoid_ros.camera_utils.PinholeCameraModel(camera_info)

Bases: PinholeCameraModel

Examples: >>> msg = sensor_msgs.msg.CameraInfo() >>> cm = PinhoneCameraModel(msg)

__init__(camera_info)
generatePointsRaw(depthImageCv, transform=None, colorImageCv=None, threshold=0.1, ROI=None)

Generates 3D points and corresponding colors from a depth image using a pinhole camera model.

Parameters:
  • depthImageCv (numpy.ndarray) – Depth image in CV format, where depth values are in millimeters.

  • transform (optional) – Transformation object to apply to the generated 3D points. Defaults to None.

  • colorImageCv (numpy.ndarray, optional) – Color image in CV format, used to extract color information for points. Defaults to None.

  • threshold (float, optional) – Minimum depth value to consider. Points with depth below this value are ignored. Defaults to 0.1.

  • ROI (sensor_msgs.msg.RegionOfInterest or tuple, optional) – Region of Interest (ROI) object specifying the area of the image to process. Defaults to None.

Returns:

A tuple containing:
  • points (list of numpy.ndarray): List of 3D points in the camera coordinate system.

  • colors (list of numpy.ndarray): List of color values corresponding to the 3D points. Empty if colorImageCv is None.

Return type:

(points, colors)

generatePoints(depthImageCv, transform=None, colorImageCv=None, threshold=0.1, ROI=None, **kwargs)

Generates SceneNode of 3D points from a depth image and optionally associates colors with the points.

Parameters:
  • depthImageCv (numpy.ndarray) – The depth image in OpenCV format.

  • transform (coordinates, optional) – A transformation matrix to apply to the points. Defaults to None.

  • colorImageCv (numpy.ndarray, optional) – The color image in OpenCV format to associate colors with the points. Defaults to None.

  • threshold (float, optional) – The depth threshold to filter points. Defaults to 0.1.

  • ROI (sensor_msgs.msg.RegionOfInterest or tuple, optional) – A region of interest specified as (x, y, width, height). Defaults to None.

  • **kwargs – Additional keyword arguments to pass to the mkshapes.makePoints function.

Returns:

A points object created by mkshapes.makePoints, containing the generated 3D points and optionally their associated colors.

Return type:

object

irsl_choreonoid_ros.camera_utils.cameraModelFromCameraInfo(camera_info)

Generate Camera-model from a CameraInfo message

Parameters:

camera_info (sensor_msgs.msg.CameraInfo) – The CameraInfo message

Returns:

An instance of PinholeCameraModel initialized with

the parameters from the provided CameraInfo message.

Return type:

PinholeCameraModel

irsl_choreonoid_ros.point_utils

https://github.com/IRSL-tut/irsl_choreonoid_ros/blob/main/irsl_choreonoid_ros/point_utils.py

irsl_choreonoid_ros.point_utils.convertPointCloud2ToPointsRaw(pc2msg, skip_nans=True, nanValue=None, ROI=None, addColor=True)

Converts a PointCloud2 ROS message into raw points and optionally extracts colors.

Parameters:
  • pc2msg (sensor_msgs.msg.PointCloud2) – The PointCloud2 message to be converted.

  • skip_nans (bool, optional) – If True, skips points with NaN values. Defaults to True.

  • nanValue (float, optional) – Value to replace NaNs with if skip_nans is False. Defaults to None.

  • ROI (tuple, optional) – Region of interest specified as (x, y, width, height). If provided, only points within this ROI are processed. Defaults to None.

  • addColor (bool, optional) – If True, extracts RGB color information from the point cloud if available. Defaults to True.

Returns:

A tuple containing:
  • points (list of numpy.ndarray): A list of 3D points as numpy arrays [x, y, z].

  • colors (list of numpy.ndarray): A list of RGB colors as numpy arrays [r, g, b]. Empty if addColor is False or no color information is available.

Return type:

tuple

Raises:

ValueError – If the ROI is invalid or out of bounds.

irsl_choreonoid_ros.point_utils.convertPointCloud2ToPoints(pc2msg, skip_nans=True, nanValue=None, ROI=None, addColor=True, **kwargs)

Converts a PointCloud2 ROS message to SgPoint

Parameters:
  • pc2msg (sensor_msgs.msg.PointCloud2) – The PointCloud2 message to be converted.

  • skip_nans (bool, optional) – If True, skips points with NaN values. Defaults to True.

  • nanValue (float, optional) – Value to replace NaNs with, if skip_nans is False. Defaults to None.

  • ROI (tuple, optional) – Region of Interest specified as a tuple (xmin, xmax, ymin, ymax, zmin, zmax). If provided, only points within this region are included. Defaults to None.

  • addColor (bool, optional) – If True, extracts color information from the PointCloud2 message. Defaults to True.

  • **kwargs – Additional keyword arguments passed to the mkshapes.makePoints function.

Returns:

A point cloud shape created using the processed points and colors.

Return type:

object

irsl_choreonoid_ros.point_utils.convertLaserScanToPointsRaw(lsmsg, useIntensities=False, maxIntensity=1.0, maxColor=None, minColor=None, skip_inf=True)

Converts a LaserScan ROS message into a list of 2D points and optionally their corresponding colors.

Parameters:
  • lsmsg (LaserScan) – The LaserScan message containing range and intensity data.

  • useIntensities (bool, optional) – Whether to use intensity values to compute colors. Defaults to False.

  • maxIntensity (float, optional) – The maximum intensity value for normalization. Defaults to 1.0.

  • maxColor (numpy.ndarray, optional) – The RGB color corresponding to maximum intensity. Defaults to [0., 1., 0.] (green).

  • minColor (numpy.ndarray, optional) – The RGB color corresponding to minimum intensity. Defaults to [1., 0., 0.] (red).

  • skip_inf (bool, optional) – Whether to skip points with infinite range values. Defaults to True.

Returns:

A tuple containing:
  • points (list of numpy.ndarray): A list of 2D points in the form [x, y, z=0].

  • colors (list of numpy.ndarray): A list of RGB colors corresponding to the points (empty if useIntensities is False).

Return type:

tuple

irsl_choreonoid_ros.point_utils.convertLaserScanToPoints(lsmsg, useIntensities=False, maxIntensity=1.0, maxColor=None, minColor=None, skip_inf=True, **kwargs)

Converts a LaserScan ROS message to SgPoint

Parameters:
  • lsmsg (sensor_msgs.msg.LaserScan) – The LaserScan message to be converted.

  • useIntensities (bool, optional) – Whether to use intensity values for coloring the points. Defaults to False.

  • maxIntensity (float, optional) – The maximum intensity value for scaling colors. Defaults to 1.0.

  • maxColor (tuple or list, optional) – The RGB color corresponding to the maximum intensity. Defaults to None.

  • minColor (tuple or list, optional) – The RGB color corresponding to the minimum intensity. Defaults to None.

  • skip_inf (bool, optional) – Whether to skip points with infinite range values. Defaults to True.

  • **kwargs – Additional keyword arguments to be passed to the mkshapes.makePoints function.

Returns:

A points object created by mkshapes.makePoints, containing the 3D points and optional colors.

Return type:

object

irsl_choreonoid_ros.tf_utils

https://github.com/IRSL-tut/irsl_choreonoid_ros/blob/main/irsl_choreonoid_ros/tf_utils.py

class irsl_choreonoid_ros.tf_utils.TransformListener(*args, **kwargs)

Bases: TransformListener

A custom TransformListener class that extends tf.TransformListener to provide additional utility methods for working with coordinate(IRSL)

__init__(*args, **kwargs)

Initializes the TransformListener instance.

Parameters:
  • *args – Variable length argument list passed to tf.TransformListener class.

  • **kwargs – Arbitrary keyword arguments passed to tf.TransformListener class.

Notes

interpolate (bool, default=True) : cache_time (float, optional) : time of cache

lookupCoords(target_frame, source_frame, rostime)

Looks up the transformation between two frames and returns it as coordinates.

Parameters:
  • target_frame (str) – The name of the target frame.

  • source_frame (str) – The name of the source frame.

  • rostime (rospy.Time) – The time at which to perform the lookup.

Returns:

A coordinates object containing the translation and rotation.

Return type:

coordinates

waitForCoords(origin_frame, target_frame, rostime, timeout_sec=1.0)

Waits for a transformation between two frames to become available. (Raise exception if failed)

Parameters:
  • origin_frame (str) – The name of the origin frame.

  • target_frame (str) – The name of the target frame.

  • rostime (rospy.Time) – The time at which to wait for the transformation.

  • timeout_sec (float, optional) – The timeout duration in seconds. Defaults to 1.0.

tryWaiting(origin_frame, target_frame, rostime, timeout_sec=1.0)

Attempts to wait for a transformation between two frames to become available. (Return True if the transformation was found)

Parameters:
  • origin_frame (str) – The name of the origin frame.

  • target_frame (str) – The name of the target frame.

  • rostime (rospy.Time) – The time at which to wait for the transformation.

  • timeout_sec (float, optional) – The timeout duration in seconds. Defaults to 1.0.

Returns:

True if the transformation becomes available, False otherwise.

Return type:

bool

class irsl_choreonoid_ros.tf_utils.TransformBroadcaster(*args, **kwargs)

Bases: TransformBroadcaster

A custom TransformBroadcaster class that extends tf.TransformBroadcaster to provide additional utility methods for working with coordinate(IRSL)

__init__(*args, **kwargs)

Initializes the TransformListener instance.

Parameters:
  • *args – Variable length argument list passed to tf.TransformBroadcaster class.

  • **kwargs – Arbitrary keyword arguments passed to tf.TransformBroadcaster class.

sendCoords(coords, rostime, child, parent)

Sends the coordinates as TF

Parameters:
  • coords (object) – An object containing pos (position as a list of 3 floats) and quaternion (rotation as a list of 4 floats).

  • rostime (rospy.Time) – The timestamp for the transform.

  • child (str) – The child frame ID.

  • parent (str) – The parent frame ID.

Returns:

True if the transform was successfully sent, False otherwise.

Return type:

bool

irsl_choreonoid_ros.setup_cnoid

https://github.com/IRSL-tut/irsl_choreonoid_ros/blob/main/irsl_choreonoid_ros/setup_cnoid.py

class irsl_choreonoid_ros.setup_cnoid.SetupCnoid(rootItem=None, worldItem=None)

Bases: SetupCnoid

__init__(rootItem=None, worldItem=None)
Parameters:
  • rootItem (cnoid.Base.Item, optional) – If set, it is used as root for creating environment

  • worldItem (cnoid.Base.WorldItem, optional) – If set, it is used as a worldItem

addExtraWorld(world_info)

abstract method

irsl_choreonoid_ros.convert_msgs

https://github.com/IRSL-tut/irsl_choreonoid_ros/blob/main/irsl_choreonoid_ros/convert_msgs.py

irsl_choreonoid_ros.convert_msgs.convertToROSMsg(pyexpr, class_rosmsg, **kwargs)

Converts a Python expression to a ROS message of the specified type.

Parameters:
  • pyexpr – The Python expression to be converted.

  • class_rosmsg – The ROS message class to which the Python expression should be converted.

  • **kwargs – Additional keyword arguments to be passed to the conversion function.

Returns:

The converted ROS message.

Raises:

Exception – If the ROS message class is not found in the conversion function map.

irsl_choreonoid_ros.convert_msgs.convertFromROSMsg(rosmsg)

Converts a ROS message to a corresponding format using a predefined mapping.

Parameters:

rosmsg (object) – The ROS message to be converted.

Returns:

The converted message using the corresponding function from __from_function_map__.

Return type:

object

Raises:

Exception – If the ROS message’s class MD5 checksum is not found in __from_function_map__.

Notes

This function checks if the ROS message’s class MD5 checksum exists in the __from_function_map__ dictionary. If a matching function is found, it is used to convert the ROS message. Otherwise, an exception is raised.

irsl_choreonoid_ros.RobotInterface

https://github.com/IRSL-tut/irsl_choreonoid_ros/blob/main/irsl_choreonoid_ros/RobotInterface.py

class irsl_choreonoid_ros.RobotInterface.MobileBaseInterface(info, robot=None, **kwargs)

Bases: object

Interface for controlling locomotion of the robot

__init__(info, robot=None, **kwargs)
property mobile_initialized

Initialized check of MobileBase

Returns:

True returns, if MobileBase instance has been initialized

Return type:

boolean

property mobile_connected

Connection check of MobileBase

Returns:

True returns, if MobileBase instance has been connected

Return type:

boolean

waitFinishMoving(timeout=1.0)

Wait to finish moving of MobileBase

Parameters:

timeout (float, default=1.0)

Returns:

False returns, if timeout.

Return type:

boolean

stop()

Stop moving of MobileBase

Parameters:

None

move_velocity(vel_x, vel_y, vel_th)

Set moving velocity of MobileBase

Parameters:
  • vel_x (float) – Velocity of x-axis [ m/sec ]

  • vel_y (float) – Velocity of y-axis [ m/sec ]

  • vel_th (float) – Angular velocity of yaw [ radian/sec ]

property currentCoordsOnMap

Current robot’s coordinate on the map frame

Returns:

Current robot’s coordinate on the map

Return type:

cnoid.IRSLCoords.coordinates

property currentCoordsOnOdom

Current robot’s coordinate on the odom frame

Returns:

Current robot’s coordinate on the odom

Return type:

cnoid.IRSLCoords.coordinates

coordsOnMap(time=None)

Current robot’s coordinate on the map frame

Parameters:

time (rospy.Time, optional) – Time using to solve TF

Returns:

Current robot’s coordinate on the map

Return type:

cnoid.IRSLCoords.coordinates

coordsOnOdom(time=None)

Current robot’s coordinate on the odom frame

Parameters:

time (rospy.Time, optional) – Time using to solve TF

Returns:

Current robot’s coordinate on the odom

Return type:

cnoid.IRSLCoords.coordinates

move_position(coords, wrt=<wrt.local: 1>)

Set target position for MobileBase, target is reletive to current robot’s coordinates

Parameters:

coords (cnoid.IRSLCoords.coordinates) – Target coordinates for moving (reletive to current robot’s coordinates)

move_on_map(coords, relative=False, time=None, wrt=<wrt.local: 1>)

Set target position on map for MobileBase, target is relative to map coordinates

Parameters:
  • coords (cnoid.IRSLCoords.coordinates) – Target coordinates for moving (map coordinates)

  • relative (boolean, default = False) – If True, trajectory is considered it is relative to robot’s coordinates.

  • time (rospy.Time, optional) – If relative is True, use this time to solve tf

  • () (wrt)

wait_move_on_map(timeout=None)

Wait until move_on_map method finished

Parameters:

timeout (float, optional) – If set, maximum waiting time is set

move_trajectory_map(trajectory, relative=False, time=None, wrt=<wrt.local: 1>)

Set target trajectory (based on tf of map) for MobileBase (odometry relative move)

Parameters:
  • trajectory (list[(cnoid.IRSLCoords.coordinates, float)]) – List of pair of coordinates and time

  • relative (boolean, default = False) – If True, trajectory is considered it is relative to robot’s coordinates.

  • time (rospy.Time, optional) – If relative is True, use this time to solve tf

  • () (wrt)

move_trajectory(trajectory, relative=False, time=None, wrt=<wrt.local: 1>)

Set target trajectory for MobileBase (odometry relative move)

Parameters:
  • trajectory (list[(cnoid.IRSLCoords.coordinates, float)]) – List of pair of coordinates and time

  • relative (boolean, default = False) – If True, trajectory is considered it is relative to robot’s coordinates.

  • time (rospy.Time, optional) – If relative is True, use this time to solve tf

  • () (wrt)

wait_move_trajectory(timeout=None)

Wait until move_trajectory method finished

Parameters:

timeout (float, optional) – If set, maximum waiting time is set

class irsl_choreonoid_ros.RobotInterface.JointInterface(info, robot=None, **kwargs)

Bases: object

Interface for controlling joints of the robot

__init__(info, robot=None, **kwargs)
property joint_initialized

Initialized check of JointInterface

Returns:

True returns, if JointInterface instance has been initialized

Return type:

boolean

property joint_connected

Connection check of JointInterface

Returns:

True returns, if JointInterface instance has been connected

Return type:

boolean

property jointGroupList

Getting list of instance of joint-group

Returns:

List of instance of joint-groups

Return type:

list [ JointGroup ]

property jointGroupNames

Getting list of name of joint-groups

Returns:

List of name of joint-groups

Return type:

list [ str ]

getJointGroup(name)

Getting a instance of joint-group

Parameters:

name (str) – Name of joint-group

Returns:

Instance of joint-group

Return type:

JointGroupTopic

sendAngles(tm=None, group=None)

Sending angles of self.robot to the actual robot

Parameters:
  • tm (float) – Moving duration in second

  • group (str or list[str], optional) – Name(s) of group to be used

sendAngleVector(angle_vector, tm=None, group=None, wait=False, waitTimeout=None)

Sending angle-vector to the actual robot. angle_vector is set to self.robot

Parameters:
  • angle_vector (numpy.array) – Vector of angles of whole body

  • tm (float) – Moving duration in second

  • group (str or list[str], optional) – Name(s) of group to be used

  • wait (boolean, defaut=False) – Wait until finishing moveving

  • waitTimeout (float, optional) – Pass to waitUntilFinish

sendAngleVectorSequence(angle_vector_list, tm_list, group=None, wait=False, waitTimeout=None)
Parameters:
  • angle_vector_list (list [numpy.array]) – List of vectors of angles

  • tm_list (list[ float ]) – List of moving durations in second

  • group (str or list[str], optional) – Name(s) of group to be used

  • wait (bolean, default=False) – wait until finishing move

  • waitTimeout (float, optional) – Pass to waitUntilFinish

sendAngleMap(angle_map, tm, group=None, wait=False, waitTimeout=None)

Sending angles to the actual robot. angles is set to self.robot

Parameters:
  • angle_map (dict[name, float]) – Dictionary, whose key is joint-name, and value is joint-angle

  • tm (float) – Moving duration in second

  • group (str or list[str], optional) – Name(s) of group to be used

isFinished(group=None)

Checking method for finishing to send angles

Parameters:

group (str or list[str], optional) – Name(s) of group to be used

Returns:

If True, the robot is not moving

Return type:

boolean

waitUntilFinish(timeout=None, group=None)

Waiting until finishing joint moving

Parameters:
  • timeout (float, optional) – Time for timeout

  • group (str or list[str], optional) – Name(s) of group to be used

Returns:

False returns, if timeout.

Return type:

boolean

class irsl_choreonoid_ros.RobotInterface.DeviceInterface(info, robot=None, **kwargs)

Bases: object

Interface for receiving data from sensors on the robot

__init__(info, robot=None, **kwargs)
property device_initialized

Initialized check of DeviceInterface

Returns:

True returns, if DeviceInterface instance has been initialized

Return type:

boolean

property device_connected

Connection check of DeviceInterface

Returns:

True returns, if all devices in this instance have been connected

Return type:

boolean

property deviceList

Getting list of the instances for gathering data from the device

Returns:

List of the instances for gathering data

Return type:

list [ RosDeviceBase ]

property deviceNames

Getting list of name of the devices

Returns:

List of name of the devices

Return type:

list [ str ]

getDevice(name)

Getting the instance for gathering data from the device

Parameters:

name (str) – Name of the device

Returns:

The instance witch has the same name as given name

Return type:

RosDeviceBase

getDevicesByClass(cls)

Getting the list of device which is a typical class

Parameters:

cls (Class) – Class of the device

Returns:

List of the instance whose class is subclass of cls

Return type:

list [obj]

data(name, clear=False)

Getting data from the device

Parameters:
  • name (str) – Name of the device

  • clear (boolean, default = False) – Clear current-data

Returns:

Data from the device. Type of a return value depends on type of the devide.

Return type:

ANY

waitData(name, timeout=None, clear=False)

Getting data, waiting if there is no current data

Parameters:
  • name (str) – Name of the device

  • timeout (float, optional) – Time out in second

  • clear (boolean, default = False) – Clear current-data

Returns:

Data from the device. Type of a return value depends on type of the devide.

Return type:

ANY

waitNextData(name, timeout=None, clear=False)

Getting data, waiting until subscribing new data

Parameters:
  • name (str) – Name of the device

  • timeout (float, optional) – Time out in second

  • clear (boolean, default = False) – Clear current-data

Returns:

Data from the device. Type of a return value depends on type of the devide.

Return type:

ANY

dataArray(names, clear=False)

Getting list of data from devices

Parameters:
  • names (list[str]) – Name of the device

  • clear (boolean, default = False) – Clear current-data

Returns:

Data from the device. Type of a return value depends on type of the devide.

Return type:

list[ANY]

waitDataArray(names, timeout=None, clear=False)

Getting list of data, waiting if there is no current data

Parameters:
  • names (list[str]) – Name of the device

  • timeout (float, optional) – Time out in second

  • clear (boolean, default = False) – Clear current-data

Returns:

Data from the device. Type of a return value depends on type of the devide.

Return type:

ANY

waitNextDataArray(names, timeout=None, clear=False)

Getting list of data, waiting until subscribing new data

Parameters:
  • names (list[str]) – Name of the device

  • timeout (float, optional) – Time out in second

  • clear (boolean, default = False) – Clear current-data

Returns:

Data from the device. Type of a return value depends on type of the devide.

Return type:

ANY

addDevice(dev, force=False)

Adding device to

Parameters:
  • dev (RosDeviceBase) – Instance of device

  • force (boolean, default=False) – If True, overwrite when duplicate

Returns

boolean : Returns True if device was added successfully

removeDevice(devname, purge=True)

Removing device from

Parameters:
  • devname (str) – Name of device

  • purge (boolean, default=True) – If True, destruct device object

Returns:

Returns True if device was removed successfully

Return type:

boolean

class irsl_choreonoid_ros.RobotInterface.OneShotSubscriber(topic, msg, size=1, **kwargs)

Bases: RosDeviceBase

Subscribe just N messages

__init__(topic, msg, size=1, **kwargs)

” :param topic: Name of Topic :type topic: str :param msg: Class instance of message to subscribe :type msg: class :param size: Size of messages to be subscribed :type size: int, default = 1

waitResults(timeout=None)

“Waiting N results

Parameters:
  • topic (str) – Name of Topic

  • msg (class) – Class instance of message to subscribe

  • size (int, default = 1) – Size of messages to be subscribed

Returns:

Subscribed messages. If timeout occurs, None is returned.

Return type:

list( ros_message )

class irsl_choreonoid_ros.RobotInterface.OneShotSyncSubscriber(topics, msgs, size=1, sync_message_queue_size=100, sync_slop=0.02)

Bases: RosDeviceBase

Subscribe just N sync messages

__init__(topics, msgs, size=1, sync_message_queue_size=100, sync_slop=0.02)

” :param topics: Name of Topic :type topics: list of str :param msgs: Class instance of message to subscribe :type msgs: list of class :param size: Size of messages to be subscribed :type size: int, default = 1 :param sync_message_queue_size: Size of message queue :type sync_message_queue_size: int, default = 100 :param sync_slop: Delay with which messages can be synchronized in seconds). :type sync_slop: float, default = 0.02

waitResults(timeout=None)

“Waiting N results

Parameters:

timeout (float, default = None) – Time for timeout

Returns:

None

class irsl_choreonoid_ros.RobotInterface.RobotInterface(file_name, node_name='robot_interface', anonymous=False, connection_wait=3.0, connection=True, MASTER_URI=None, MASTER=None, MASTER_PORT=11311, IP=None, HOSTNAME=None)

Bases: JointInterface, DeviceInterface, MobileBaseInterface

Interface for controllring robot (inheriting classes JointInterface, DeviceInterface and MobileBaseInterface)

At a instance of this interface, all methods in JointInterface, DeviceInterface and MobileBaseInterface can be used.

Then, please refer methods of these classes.

__init__(file_name, node_name='robot_interface', anonymous=False, connection_wait=3.0, connection=True, MASTER_URI=None, MASTER=None, MASTER_PORT=11311, IP=None, HOSTNAME=None)
Parameters:
  • file_name (str) – Name of setting.yaml file

  • node_name (str, default='robot_interface') – Name of node

  • anonymous (boolean, default = False) – If True, ROS node will start with this node-name.

  • connection_wait (float, default=3.0) – Wait until ROS connection has established

  • connection (boolean, default=True) – If false, create instance without ROS connection

  • MASTER_URI (str, optional) – Set environment variable, ROS_MASTER_URI if MASTER is not set

  • MASTER (str, optional) – Set environment variable, ROS_MASTER_URI = http://MASTER:MASTER_PORT

  • MASTER_PORT (int, default 11311) – Set environment variable, ROS_MASTER_URI = http://MASTER:MASTER_PORT

  • IP (str, optional) – Set environment variable, ROS_IP

  • HOSTNAME (str, optional) – Set environment variable, ROS_HOSTNAME

getRobotModel(asItem=True)

Return an instance of RobotModel (irsl_choreonoid.robot_util.RobotModelWrapped)

Parameters:

asItem (boolean, default=True) – If True, model is generated as cnoid.BodyPlugin.BodyItem

Returns:

Newly generated instance

Return type:

irsl_choreonoid.robot_util.RobotModelWrapped

getActualRobotModel(asItem=True)

Return an instance of RobotModel (irsl_choreonoid.robot_util.RobotModelWrapped) with RobotInterface internal robot-model

Parameters:

asItem (boolean, default=True) – If True, model is generated as cnoid.BodyPlugin.BodyItem

Returns:

RobotModel created from RobotInterface internal robot-model

Return type:

irsl_choreonoid.robot_util.RobotModelWrapped

copyRobot()

Return other instance of the robot model

Parameters:

None

Returns:

Copy of self.robot (this is not identical to self.robot)

Return type:

cnoid.Body.Body

isRealRobot()

Checking this interface working with a real robot

Parameters:

None

Retuns:

boolean : If True, this interface connected to a real robot, otherwise connected to simulator

property effortVector

Return vector of effort of actual robot (sensing value)

This method requires JointState class in devices

Returns:

1 x N vector ( N is len(jointList) )

Return type:

numpy.array

property velocityVector

Return vector of velocity of actual robot (sensing value)

This method requires JointState class in devices

Returns:

1 x N vector ( N is len(jointList) )

Return type:

numpy.array

property actualAngleVector

Return angle-vector of actual robot (sensing value)

This method requires JointState class in devices

Returns:

1 x N vector ( N is len(jointList) )

Return type:

numpy.array

property referenceAngleVector

Return reference angle-vector (value of past command)

This method requires JointTrajectoryState class in devices

Returns:

1 x N vector ( N is len(jointList) )

Return type:

numpy.array

property robot

Return instance of the robot model (applying sensor values)

Returns:

Instance of the robot model using in this instance

Return type:

cnoid.Body.Body

property jointRobot

Return instance of the robot model (using for sending command)

Returns:

Instance of the robot model using in this instance

Return type:

cnoid.Body.Body

oneShotSubscriber(topic, msg, size=1)

Return instance of OneShotSubscriber

Parameters:
  • topic (str) – Name of Topic

  • msg (class) – Class instance of message to subscribe

  • size (int, default = 1) – Size of messages to be subscribed

Returns:

Instance of OneShotSubscriber

Return type:

OneShotSubscriber

Examples

one = ri.oneShotSubscriber(‘topicname’, sensor_msgs.msg.Image) res = one.waitResults(5)

oneShotSyncSubscriber(topics, msgs, size=1, sync_message_queue_size=100, sync_slop=0.02)

” :param topic: Name of Topic :type topic: list of str :param msg: Class instance of message to subscribe :type msg: list of class :param size: Size of messages to be subscribed :type size: int, default = 1 :param sync_message_queue_size: Size of message queue :type sync_message_queue_size: int, default = 100 :param sync_slop: Delay with which messages can be synchronized in seconds) :type sync_slop: float, default = 0.02

Returns:

Instance of OneShotSyncSubscriber

Return type:

OneShotSyncSubscriber

Examples

one = ri.oneShotSyncSubscriber([‘topicname1’, ‘topicname2’], [sensor_msgs.msg.Image, sensor_msgs.msg.CameraInfo]) res = one.waitResults(5)

getRosDevice(topic, msg, name=None)
Parameters:
  • topic (str) – Name of Topic

  • msg (class) – Class instance of message to subscribe

  • name (str, default = 'rosdevice') – Name of device

Returns:

Instance of RosDevice

Return type:

RosDevice

Examples

dev = ri.getRosDeivce(‘topicname’, sensor_msgs.msg.Image, name=’Camera0’) res = dev.getNextData(5)