morse.middleware.ros package

Submodules

morse.middleware.ros.abstract_ros module

class AbstractROS(component_instance, kwargs)[source]

Bases: morse.middleware.abstract_datastream.AbstractDatastream

Base class for all ROS Publishers and Subscribers

finalize()[source]

Cleaning

get_topic_name()[source]
initialize()[source]

initialize the specific datastream

Can be overriden if needed

ros_class

alias of std_msgs.msg._Header.Header

class ROSPublisher(component_instance, kwargs)[source]

Bases: morse.middleware.ros.abstract_ros.AbstractROS

Base class for all ROS Publishers

default_frame_id = 'USE_TOPIC_NAME'
determine_queue_size()[source]

Determine a suitable queue_size for the ros publisher :return: queue_size

get_ros_header()[source]
get_time()[source]
initialize()[source]

initialize the specific datastream

Can be overriden if needed

publish(message)[source]

Publish the data on the rostopic

class ROSPublisherTF(component_instance, kwargs)[source]

Bases: morse.middleware.ros.abstract_ros.ROSPublisher

Base class for all ROS Publishers with TF support

finalize()[source]

Cleaning

get_robot_transform()[source]

Get the transformation relative to the robot origin

Return the local position, orientation and scale of this components

initialize()[source]

initialize the specific datastream

Can be overriden if needed

publish_tf(message)[source]

Publish the TF data on the rostopic

publish_with_robot_transform(message)[source]
sendTransform(translation, rotation, time, child, parent)[source]
Parameters:
  • translation – the translation of the transformtion as geometry_msgs/Vector3
  • rotation – the rotation of the transformation as a geometry_msgs/Quaternion
  • time – the time of the transformation, as a rospy.Time()
  • child – child frame in tf, string
  • parent – parent frame in tf, string

Broadcast the transformation from tf frame child to parent on ROS topic "/tf".

send_transform_robot(time=None, child=None, parent=None)[source]

Send the transformation relative to the robot

Parameters:
  • time – default now
  • child – default topic_name or ‘frame_id’ in kwargs
  • parent – default ‘base_link’ or ‘parent_frame_id’ in kwargs
topic_tf = None
class ROSSubscriber(component_instance, kwargs)[source]

Bases: morse.middleware.ros.abstract_ros.AbstractROS

Base class for all ROS Subscribers

callback(message)[source]
default(ci='unused')[source]

default method called by MORSE logic

Sensor: must read local_data, format and publish them. Actuator: must read a new incoming command and update local_data.

initialize()[source]

initialize the specific datastream

Can be overriden if needed

update(message)[source]

Update local_data with :param message:

Called when component.default_action is triggered and a new message was received

class StringPublisher(component_instance, kwargs)[source]

Bases: morse.middleware.ros.abstract_ros.ROSPublisher

Publish a string containing a printable representation of the local data.

default(ci='unused')[source]

default method called by MORSE logic

Sensor: must read local_data, format and publish them. Actuator: must read a new incoming command and update local_data.

ros_class

alias of std_msgs.msg._String.String

class StringReader(component_instance, kwargs)[source]

Bases: morse.middleware.ros.abstract_ros.ROSSubscriber

Subscribe to a String topic and log its data decoded as UTF-8.

ros_class

alias of std_msgs.msg._String.String

update(message)[source]

Update local_data with :param message:

Called when component.default_action is triggered and a new message was received

class classproperty(fget)[source]

Bases: object

morse.middleware.ros.accelerometer module

class AccelWithCovarianceStampedPublisher(component_instance, kwargs)[source]

Bases: morse.middleware.ros.abstract_ros.ROSPublisher

default(ci='unused')[source]

default method called by MORSE logic

Sensor: must read local_data, format and publish them. Actuator: must read a new incoming command and update local_data.

ros_class

alias of geometry_msgs.msg._AccelWithCovarianceStamped.AccelWithCovarianceStamped

class TwistPublisher(component_instance, kwargs)[source]

Bases: morse.middleware.ros.abstract_ros.ROSPublisher

Publish the velocity of the acceleromter sensor. No angular information, only linear ones.

default(ci='unused')[source]

default method called by MORSE logic

Sensor: must read local_data, format and publish them. Actuator: must read a new incoming command and update local_data.

ros_class

alias of geometry_msgs.msg._TwistStamped.TwistStamped

morse.middleware.ros.battery module

class Float32Publisher(component_instance, kwargs)[source]

Bases: morse.middleware.ros.abstract_ros.ROSPublisher

Publish the charge of the battery sensor.

default(ci='unused')[source]

default method called by MORSE logic

Sensor: must read local_data, format and publish them. Actuator: must read a new incoming command and update local_data.

ros_class

alias of std_msgs.msg._Float32.Float32

morse.middleware.ros.clock module

class ClockPublisher(component_instance, kwargs)[source]

Bases: morse.middleware.ros.abstract_ros.ROSPublisher

Publish the simulator clock.

default(ci='unused')[source]

default method called by MORSE logic

Sensor: must read local_data, format and publish them. Actuator: must read a new incoming command and update local_data.

initialize()[source]

initialize the specific datastream

Can be overriden if needed

ros_class

alias of rosgraph_msgs.msg._Clock.Clock

morse.middleware.ros.depth_camera module

class DepthCameraPublisher(component_instance, kwargs)[source]

Bases: morse.middleware.ros.abstract_ros.ROSPublisherTF

Publish the depth field from the Camera perspective as XYZ point-cloud. And send the transformation between the camera and the robot through TF.

default(ci='unused')[source]

default method called by MORSE logic

Sensor: must read local_data, format and publish them. Actuator: must read a new incoming command and update local_data.

ros_class

alias of sensor_msgs.msg._PointCloud2.PointCloud2

morse.middleware.ros.destination module

class PointReader(component_instance, kwargs)[source]

Bases: morse.middleware.ros.abstract_ros.ROSSubscriber

Subscribe to a Point topic and set x,y,z local data.

ros_class

alias of geometry_msgs.msg._Point.Point

update(message)[source]

Update local_data with :param message:

Called when component.default_action is triggered and a new message was received

morse.middleware.ros.force_torque module

class WrenchReader(component_instance, kwargs)[source]

Bases: morse.middleware.ros.abstract_ros.ROSSubscriber

Subscribe to a Wrench topic and set force and torque (x,y,z) local data.

ros_class

alias of geometry_msgs.msg._Wrench.Wrench

update(message)[source]

Update local_data with :param message:

Called when component.default_action is triggered and a new message was received

morse.middleware.ros.gps module

class NavSatFixPublisher(component_instance, kwargs)[source]

Bases: morse.middleware.ros.abstract_ros.ROSPublisher

Publish the GPS position of the robot.

default(ci='unused')[source]

default method called by MORSE logic

Sensor: must read local_data, format and publish them. Actuator: must read a new incoming command and update local_data.

ros_class

alias of sensor_msgs.msg._NavSatFix.NavSatFix

class NavSatFixRawPublisher(component_instance, kwargs)[source]

Bases: morse.middleware.ros.abstract_ros.ROSPublisher

Publish the GPS position of the robot.

default(ci='unused')[source]

default method called by MORSE logic

Sensor: must read local_data, format and publish them. Actuator: must read a new incoming command and update local_data.

ros_class

alias of sensor_msgs.msg._NavSatFix.NavSatFix

morse.middleware.ros.imu module

class ImuPublisher(component_instance, kwargs)[source]

Bases: morse.middleware.ros.abstract_ros.ROSPublisher

Publish the data of the IMU sensor (without covariance).

default(ci='unused')[source]

default method called by MORSE logic

Sensor: must read local_data, format and publish them. Actuator: must read a new incoming command and update local_data.

default_frame_id = '/imu'
ros_class

alias of sensor_msgs.msg._Imu.Imu

morse.middleware.ros.infrared module

class RangePublisher(component_instance, kwargs)[source]

Bases: morse.middleware.ros.abstract_ros.ROSPublisher

Publish the range of the infrared sensor.

default(ci='unused')[source]

default method called by MORSE logic

Sensor: must read local_data, format and publish them. Actuator: must read a new incoming command and update local_data.

ros_class

alias of sensor_msgs.msg._Range.Range

morse.middleware.ros.jido_posture module

class JointStatePublisher(component_instance, kwargs)[source]

Bases: morse.middleware.ros.abstract_ros.ROSPublisher

Publish the data of the posture sensor (for Jido).

default(ci='unused')[source]

default method called by MORSE logic

Sensor: must read local_data, format and publish them. Actuator: must read a new incoming command and update local_data.

ros_class

alias of sensor_msgs.msg._JointState.JointState

morse.middleware.ros.jointstate module

class JointStatePR2Publisher(component_instance, kwargs)[source]

Bases: morse.middleware.ros.abstract_ros.ROSPublisher

Publish the data of the posture sensor after filling missing PR2 joints.

default(ci='unused')[source]

default method called by MORSE logic

Sensor: must read local_data, format and publish them. Actuator: must read a new incoming command and update local_data.

ros_class

alias of sensor_msgs.msg._JointState.JointState

class JointStatePublisher(component_instance, kwargs)[source]

Bases: morse.middleware.ros.abstract_ros.ROSPublisher

Publish the data of the posture sensor.

default(ci='unused')[source]

default method called by MORSE logic

Sensor: must read local_data, format and publish them. Actuator: must read a new incoming command and update local_data.

ros_class

alias of sensor_msgs.msg._JointState.JointState

morse.middleware.ros.jointtrajectorycontrollers module

class JointTrajectoryControllerStatePublisher(component_instance, kwargs)[source]

Bases: morse.middleware.ros.abstract_ros.ROSPublisher

Publish the data of the pr2 joint sensor.

default(ci='unused')[source]

default method called by MORSE logic

Sensor: must read local_data, format and publish them. Actuator: must read a new incoming command and update local_data.

ros_class

alias of control_msgs.msg._JointTrajectoryControllerState.JointTrajectoryControllerState

morse.middleware.ros.kuka_jointstate module

class JointStateReader(component_instance, kwargs)[source]

Bases: morse.middleware.ros.abstract_ros.ROSSubscriber

Subscribe to a JointState topic and set kuka_{1-7} to the position[0-6].

ros_class

alias of sensor_msgs.msg._JointState.JointState

update(message)[source]

Update local_data with :param message:

Called when component.default_action is triggered and a new message was received

morse.middleware.ros.kuka_jointstate_pub module

class JointStatePublisher(component_instance, kwargs)[source]

Bases: morse.middleware.ros.abstract_ros.ROSPublisher

Publishes a JointState topic and set kuka_{1-7} to the position[0-6].

default(ci='unused')[source]

default method called by MORSE logic

Sensor: must read local_data, format and publish them. Actuator: must read a new incoming command and update local_data.

ros_class

alias of sensor_msgs.msg._JointState.JointState

morse.middleware.ros.laserscanner module

class LaserScanPublisher(component_instance, kwargs)[source]

Bases: morse.middleware.ros.abstract_ros.ROSPublisher

Publish the range_list of the laser scanner.

default(ci='unused')[source]

default method called by MORSE logic

Sensor: must read local_data, format and publish them. Actuator: must read a new incoming command and update local_data.

default_frame_id = '/base_laser_link'
ros_class

alias of sensor_msgs.msg._LaserScan.LaserScan

class PointCloud2Publisher(component_instance, kwargs)[source]

Bases: morse.middleware.ros.abstract_ros.ROSPublisherTF

Publish the point_list of the laser scanner.

default(ci='unused')[source]

default method called by MORSE logic

Sensor: must read local_data, format and publish them. Actuator: must read a new incoming command and update local_data.

ros_class

alias of sensor_msgs.msg._PointCloud2.PointCloud2

pack_xyz_float32(points)[source]

morse.middleware.ros.light module

class BoolReader(component_instance, kwargs)[source]

Bases: morse.middleware.ros.abstract_ros.ROSSubscriber

Subscribe to a boolean topic to control if we must or not emit light.

ros_class

alias of std_msgs.msg._Bool.Bool

update(message)[source]

Update local_data with :param message:

Called when component.default_action is triggered and a new message was received

morse.middleware.ros.motion_vw module

class TwistReader(component_instance, kwargs)[source]

Bases: morse.middleware.ros.abstract_ros.ROSSubscriber

Subscribe to a motion command and set v and w local data.

ros_class

alias of geometry_msgs.msg._Twist.Twist

update(message)[source]

Update local_data with :param message:

Called when component.default_action is triggered and a new message was received

morse.middleware.ros.motion_xyw module

class TwistReader(component_instance, kwargs)[source]

Bases: morse.middleware.ros.abstract_ros.ROSSubscriber

Subscribe to a motion command and set x, y and w local data.

ros_class

alias of geometry_msgs.msg._Twist.Twist

update(message)[source]

Update local_data with :param message:

Called when component.default_action is triggered and a new message was received

morse.middleware.ros.odometry module

class OdometryPublisher(component_instance, kwargs)[source]

Bases: morse.middleware.ros.abstract_ros.ROSPublisherTF

Publish the odometry of the robot. And send the transformation between frame_id and child_frame_id args, default ‘/odom’ and ‘/base_footprint’ through TF.

default(ci='unused')[source]

default method called by MORSE logic

Sensor: must read local_data, format and publish them. Actuator: must read a new incoming command and update local_data.

default_frame_id = '/odom'
get_orientation()[source]

Get the orientation from the local_data and return a quaternion

get_pose()[source]

Get the pose from the local_data and return a ROS Pose

get_position()[source]

Get the position from the local_data and return a ROS Vector3

get_twist()[source]

Get the twist from the local_data and return a ROS Twist

initialize()[source]

initialize the specific datastream

Can be overriden if needed

ros_class

alias of nav_msgs.msg._Odometry.Odometry

morse.middleware.ros.orientation module

class QuaternionReader(component_instance, kwargs)[source]

Bases: morse.middleware.ros.abstract_ros.ROSSubscriber

Subscribe to a Quaternion topic and set roll,pitch,yaw local data.

ros_class

alias of geometry_msgs.msg._Quaternion.Quaternion

update(message)[source]

Update local_data with :param message:

Called when component.default_action is triggered and a new message was received

morse.middleware.ros.platine module

class Vector3Reader(component_instance, kwargs)[source]

Bases: morse.middleware.ros.abstract_ros.ROSSubscriber

Subscribe to a Vector3 topic and set pan,tilt local data, according to the rotation axis (pan: y-axis, tilt: z-axis).

ros_class

alias of geometry_msgs.msg._Vector3.Vector3

update(message)[source]

Update local_data with :param message:

Called when component.default_action is triggered and a new message was received

morse.middleware.ros.pose module

class PosePublisher(component_instance, kwargs)[source]

Bases: morse.middleware.ros.abstract_ros.ROSPublisher

Publish the position and orientation of the robot as ROS geometry_msgs.Pose message.

default(ci='unused')[source]

default method called by MORSE logic

Sensor: must read local_data, format and publish them. Actuator: must read a new incoming command and update local_data.

ros_class

alias of geometry_msgs.msg._Pose.Pose

class PoseStampedPublisher(component_instance, kwargs)[source]

Bases: morse.middleware.ros.abstract_ros.ROSPublisher

Publish the position and orientation of the robot as ROS geometry_msgs.PoseStamped message.

default(ci='unused')[source]

default method called by MORSE logic

Sensor: must read local_data, format and publish them. Actuator: must read a new incoming command and update local_data.

default_frame_id = '/map'
ros_class

alias of geometry_msgs.msg._PoseStamped.PoseStamped

class PoseWithCovarianceStampedPublisher(component_instance, kwargs)[source]

Bases: morse.middleware.ros.abstract_ros.ROSPublisher

Publish the position and orientation of the robot including the covariance.

default(ci='unused')[source]

default method called by MORSE logic

Sensor: must read local_data, format and publish them. Actuator: must read a new incoming command and update local_data.

default_frame_id = '/map'
ros_class

alias of geometry_msgs.msg._PoseWithCovarianceStamped.PoseWithCovarianceStamped

class TFPublisher(component_instance, kwargs)[source]

Bases: morse.middleware.ros.abstract_ros.ROSPublisherTF

Publish the transformation between frame_id and child_frame_id args, default ‘/map’ and ‘/base_link’ through TF.

default(ci='unused')[source]

default method called by MORSE logic

Sensor: must read local_data, format and publish them. Actuator: must read a new incoming command and update local_data.

default_frame_id = '/map'
initialize()[source]

initialize the specific datastream

Can be overriden if needed

get_orientation(self)[source]

Get the orientation from the local_data and return a ROS geometry_msgs.Quaternion

get_pose(self)[source]

Get the pose from the local_data and return a ROS geometry_msgs.Pose

get_position(self)[source]

Get the position from the local_data and return a ROS geometry_msgs.Vector3

morse.middleware.ros.ptu_posture module

class JointStatePublisher(component_instance, kwargs)[source]

Bases: morse.middleware.ros.abstract_ros.ROSPublisher

Publish the data of the posture sensor as a ROS JointState message

default(ci='unused')[source]

default method called by MORSE logic

Sensor: must read local_data, format and publish them. Actuator: must read a new incoming command and update local_data.

ros_class

alias of sensor_msgs.msg._JointState.JointState

morse.middleware.ros.quadrotor_dynamic module

class QuadrotorDynamicReader(component_instance, kwargs)[source]

Bases: morse.middleware.ros.abstract_ros.ROSSubscriber

Subscribe to a float array topic and set quadrotor engines local data.

ros_class

alias of std_msgs.msg._Float32MultiArray.Float32MultiArray

update(message)[source]

Update local_data with :param message:

Called when component.default_action is triggered and a new message was received

morse.middleware.ros.read_asctec_ctrl_input module

morse.middleware.ros.read_pose module

class PoseReader(component_instance, kwargs)[source]

Bases: morse.middleware.ros.abstract_ros.ROSSubscriber

Subscribe to a Pose topic and set position as Vector and x, y, z and orientation as Quaternion and roll, pitch, yaw local data.

ros_class

alias of geometry_msgs.msg._Pose.Pose

update(message)[source]

Update local_data with :param message:

Called when component.default_action is triggered and a new message was received

class PoseStampedReader(component_instance, kwargs)[source]

Bases: morse.middleware.ros.abstract_ros.ROSSubscriber

Subscribe to a PoseStamped topic and set position as Vector and x, y, z and orientation as Quaternion and roll, pitch, yaw local data.

ros_class

alias of geometry_msgs.msg._PoseStamped.PoseStamped

update(message)[source]

Update local_data with :param message:

Called when component.default_action is triggered and a new message was received

morse.middleware.ros.read_twist module

class TwistReader(component_instance, kwargs)[source]

Bases: morse.middleware.ros.abstract_ros.ROSSubscriber

Subscribe to a Twist topic and set vx, vy, vz and vroll, vpitch, vyaw local data.

ros_class

alias of geometry_msgs.msg._Twist.Twist

update(message)[source]

Update local_data with :param message:

Called when component.default_action is triggered and a new message was received

morse.middleware.ros.rotorcraft_attitude module

class RotorcraftAttitudeReader(component_instance, kwargs)[source]

Bases: morse.middleware.ros.abstract_ros.ROSSubscriber

Subscribe to a float array topic and set quadrotor attitude controller local data.

ros_class

alias of std_msgs.msg._Float32MultiArray.Float32MultiArray

update(message)[source]

Update local_data with :param message:

Called when component.default_action is triggered and a new message was received

morse.middleware.ros.semantic_camera module

class SemanticCameraPublisher(component_instance, kwargs)[source]

Bases: morse.middleware.ros.abstract_ros.ROSPublisherTF

Publish the data of the semantic camera as JSON in a ROS String message. And send TF transform between ‘/map’ and object.name.

default(ci='unused')[source]

default method called by MORSE logic

Sensor: must read local_data, format and publish them. Actuator: must read a new incoming command and update local_data.

initialize()[source]

initialize the specific datastream

Can be overriden if needed

ros_class

alias of std_msgs.msg._String.String

class SemanticCameraPublisherLisp(component_instance, kwargs)[source]

Bases: morse.middleware.ros.abstract_ros.ROSPublisherTF

Publish the data of the semantic camera as a ROS String message, that contains a lisp-list (each field are separated by a space).

This function was designed for the use with CRAM and the Adapto group.

default(ci='unused')[source]

default method called by MORSE logic

Sensor: must read local_data, format and publish them. Actuator: must read a new incoming command and update local_data.

initialize()[source]

initialize the specific datastream

Can be overriden if needed

ros_class

alias of std_msgs.msg._String.String

morse.middleware.ros.static_tf module

class StaticTF2Publisher(component_instance, kwargs)[source]

Bases: morse.middleware.ros.static_tf.StaticTFPublisher

Publish the (static) transform between robot and this sensor/actuator, using a latched topic (TF2 convention).

default(ci='unused')[source]

default method called by MORSE logic

Sensor: must read local_data, format and publish them. Actuator: must read a new incoming command and update local_data.

init_tr = False
initialize()[source]

initialize the specific datastream

Can be overriden if needed

publish_tf(message)[source]

Publish the TF data on the rostopic

topic_tf_static = None
class StaticTFPublisher(component_instance, kwargs)[source]

Bases: morse.middleware.ros.abstract_ros.ROSPublisherTF

Publish the (static) transform between robot and this sensor/actuator with 1Hz.

child_frame_id = None
default(ci='unused')[source]

default method called by MORSE logic

Sensor: must read local_data, format and publish them. Actuator: must read a new incoming command and update local_data.

finalize()[source]

Cleaning

initialize()[source]

initialize the specific datastream

Can be overriden if needed

last_ts = 0
parent_frame_id = None

morse.middleware.ros.tfMessage module

autogenerated by genpy from tf/tfMessage.msg. Do not edit.

class tfMessage(*args, **kwds)[source]

Bases: genpy.message.Message

deserialize(str)[source]

unpack serialized message in str into this message instance :param str: byte array of serialized message, str

deserialize_numpy(str, numpy)[source]

unpack serialized message in str into this message instance using numpy for array types :param str: byte array of serialized message, str :param numpy: numpy python module

serialize(buff)[source]

serialize message into buffer :param buff: buffer, StringIO

serialize_numpy(buff, numpy)[source]

serialize message with numpy array types into buffer :param buff: buffer, StringIO :param numpy: numpy python module

transforms

morse.middleware.ros.velocity module

class TwistStampedPublisher(component_instance, kwargs)[source]

Bases: morse.middleware.ros.abstract_ros.ROSPublisher

Publish the twist of the robot.

default(ci='unused')[source]

default method called by MORSE logic

Sensor: must read local_data, format and publish them. Actuator: must read a new incoming command and update local_data.

default_frame_id = '/base_link'
ros_class

alias of geometry_msgs.msg._TwistStamped.TwistStamped

morse.middleware.ros.video_camera module

class CameraPublisher(component_instance, kwargs)[source]

Bases: morse.middleware.ros.abstract_ros.ROSPublisherTF

Publish the image from the Camera perspective. And send the intrinsic matrix information in a separate topic of type sensor_msgs/CameraInfo.

default(ci='unused')[source]

default method called by MORSE logic

Sensor: must read local_data, format and publish them. Actuator: must read a new incoming command and update local_data.

encoding = 'tbd'
finalize()[source]

Cleaning

initialize()[source]

initialize the specific datastream

Can be overriden if needed

pub_tf = True
ros_class

alias of sensor_msgs.msg._Image.Image

class DepthCameraPublisher(component_instance, kwargs)[source]

Bases: morse.middleware.ros.video_camera.CameraPublisher

encoding = '32FC1'
class VideoCameraPublisher(component_instance, kwargs)[source]

Bases: morse.middleware.ros.video_camera.CameraPublisher

encoding = 'rgba8'

morse.middleware.ros.waypoint2D module

class Pose2DReader(component_instance, kwargs)[source]

Bases: morse.middleware.ros.abstract_ros.ROSSubscriber

Subscribe to a Pose2D topic and set x, y, z local data. This is designed to be used with the waypoint actuator.

ros_class

alias of geometry_msgs.msg._Pose2D.Pose2D

update(message)[source]

Update local_data with :param message:

Called when component.default_action is triggered and a new message was received

Module contents