rviz

Utility Functions

mil_tools.draw_sphere(position: ndarray, color: ndarray, scaling: Tuple[float, float, float] = (0.11, 0.11, 0.11), m_id: int = 4, frame: str = '/base_link') None[source]

Draws a sphere in Rviz. Creates a new Marker message and publishes it to Rviz.

Parameters
  • position (np.ndarray) – A list of float that make up the point.

  • color (np.ndarray) – An array representing the color. The array should contain the r, g, b, and a values of the color.

  • scaling (Tuple[float, float, float]) – The size of the sphere, in meters.

  • m_id (id) – The marker ID. This should be unique.

  • frame (str) – The frame which the sphere is relevant to.

mil_tools.draw_ray_3d(pix_coords, camera_model: PinholeCameraModel, color: ColorRGBA, frame: str = '/stereo_front', m_id=0, length=35) None[source]

Draws a 3D ray in Rviz. Creates a new Marker message and publishes it to the Rviz topic.

Parameters
  • pix_coords – The coordinates of the pixel.

  • camera_model (PinholeCameraModel) – The camera model to derive the marker’s direction from.

  • color (ColorRGBA) – The color of the ray.

  • frame (str) – The frame that the ray is relevant to. Defaults to /stereo_font.

  • m_id (int) – The ID of the marker. Defaults to 0.

  • length (int) – The length of the ray. Defaults to 35.

mil_tools.make_ray(base: ndarray, direction: ndarray, length: int, color: List[float], frame: str = '/base_link', m_id: int = 0, **kwargs) Marker[source]

Makes a ray from a base with a direction. The ray is constructed in the wamv namespace and has an infinite lifetime.

Parameters
  • base (np.ndarray) – The base of the marker.

  • direction (np.ndarray) – The direction of the marker.

  • length (int) – The length of the ray.

  • color (List[float]) – A list containing the r, g, b, and a values of the color.

  • frame (str) – The frame that the ray is referenced from. Defaults to /base_link.

  • m_id (int) – The unique ID of the marker. Defaults to 0.

VectorToMarker

Attributes
class mil_ros_tools.vector_to_marker.VectorToMarker(vector_topic: str, marker_topic: str, length: Optional[float] = 1.0, color: List[float] = [0, 0, 1, 1])[source]

Node to subscribe to a Vector3Stamped topic and publish a rviz marker with the same content. Used to get around the fact that rviz cannot display Vector3Stamped messages.

Can be used from the command line through argparse support.

Parameters
  • vector_topic (str) – Topic of vector3stamped to subscribe to.

  • marker_topic (str) – Topic of marker to publish.

  • length (float) – Length to scale vector to. If None, leave original scale.

  • color (List[float]) – The color of the marker. The list should contain the r, g, b, and a values of the color.

length

The length to scale the marker to upon receival.

Type

Optional[float]

pub

The publisher responsible for publishing the Marker messages.

Type

rospy.Publisher

ClickedPointRecorder

Methods
class nodes.clicked_point_recorder.ClickedPointRecorder[source]

Listens to RVIZ clicked points, storing points in a CSV file. Support for running through rosrun.

point_cb(point: PointStamped) None[source]

Serves as a callback to the point subscriber. Accepts PointStamped messages and adds the messages to the internal points array.

Parameters

point (PointStamped) – The message input to the callback.

point_to_dict(point: PointStamped) Dict[str, Union[str, int, float]][source]

Returns a dictionary representing a point, where the values for the dict are obtained from the PointStamped message accepted.

Parameters

point (PointStamped) – The point message to accept.

Returns

Dictionary representing point and stamp.

Return type

Dict[str, Union[str, int, float]]

write_file() None[source]

Writes the points to a CSV file.

NetworkBroadcaster

class nodes.network_broadcaster.NetworkBroadcaster[source]

Class to push header messages to the network topic. Heartbeat monitors check for recurring messages in other classes.