mil_poi - POI Handling

The MIL POI system is used to keep track of relevant points of interest across a landscape. This can be used to give a robotic system a headstart in determining the final target of a mission; for example, a robotic system could be instructed to head to a specific POI before looking around more closely to find the actual object it needs to interact with.

/poi_server/add

mil_poi.srv.AddPOIRequestmil_poi.srv.AddPOIResponse

Add a POI object into the POI server listing.

/poi_server/delete

mil_poi.srv.DeletePOIRequestmil_poi.srv.DeletePOIResponse

Deletes a POI with the given name, and returns whether the deletion was successful.

/poi_server/move

mil_poi.srv.MovePOIRequestmil_poi.srv.MovePOIResponse

Moves a POI with the given name to the given position, and returns whether the move was successful.

/points_of_interest/update

visualization_msgs.msg.InteractiveMarkerUpdate

Sends updates about changes to interactive markers. When attempting to view interactive markers in Rviz, the update_topic parameter of the Interactive Markers panel needs to be set to this topic.

Using with Rviz

To view and interactive with interactive marker POIs in Rviz, you will need to enable the “Interactive Markers” panel in Rviz. You will then need to set the update topic to be equal to the update topic published by the interactive marker server published by the POI server. This topic name will likely end in /update.

All POIs are represented as spheres in the interactive marker server; you can move these spheres around to change their location. Note that points are currently fixed to the x and y axes, meaning that you can not have floating or submerged points.

Configuration Files

When the POI server is launched, it is provided with several ROS parameters to describe how the server should function. This includes POIs that are spawned by default upon server initialization.

The default format of the POI configuration file is the following format:

---
global_frame: enu # Name of the frame to derive POI locations from
initial_pois: # List of POIs that are spawned by default
  start_gate: [0, 0, 0] # Name (key) and location (value) of specific POIs

POIServer

class mil_poi.POIServer[source]

Node to act as a server to hold a list of points of interest which can be modified by services or interactive markers.

marker_scale

Radius of interactive markers for POIs. Defaults to 0.5.

Type

float

add_poi_cb(req: AddPOIRequest) AddPOIResponse[source]

Callback for the AddPOI service.

Parameters

req (AddPOIRequest) – The service request. The name and position are used from the request.

Returns

Whether the operation was successful, along with a message indicating why.

Return type

AddPOIResponse

delete_poi_cb(req: DeletePOIRequest) DeletePOIResponse[source]

Callback for DeletePOI service. Equivalent to calling remove_poi().

Parameters

req (DeletePOIRequest) – The service request. The name is used to determine which POI to remove.

Returns

Whether the operation was successful, along with a message indicating why.

Return type

DeletePOIResponse

move_poi_cb(req: MovePOIRequest) MovePOIResponse[source]

Callback for MovePOI service.

Parameters

req (MovePOIRequest) – The service request.

Returns

The response from the service.

Return type

MovePOIResponse

process_feedback(feedback: InteractiveMarkerFeedback) None[source]

Process interactive marker feedback, moving markers internally in response to markers moved in Rviz.

Parameters

feedback (InteractiveMarkerFeedback) – The feedback message.

transform_position(ps: PointStamped) Optional[Point][source]

Attempt to transform a PointStamped message into the global frame, returning the position of the transformed point or None if transform failed.

Parameters

ps (PointStamped) – The PointStamped message to be transformed into the global frame.

Returns

The point in the global frame, or None if the transform experienced an exception.

Return type

Optional[Point]

update() None[source]

Update interactive markers server and POI publish of changes.

TxPOIClient

Methods
class mil_poi.TxPOIClient(nh: NodeHandle)[source]

Client for getting the positions of POIs in a POI server.

Parameters

nh (axros.NodeHandle) – The node handle to use.

async get(name: str, only_fresh: bool = False) tuple[np.ndarray, np.ndarray][source]

Get the position of POI in the global frame as a 3x1 numpy array.

Parameters
  • name (str) – The name of the POI.

  • only_fresh (bool) – If the POI is already known, wait for a fresh message before returning.

async setup() None[source]

Sets up the client. Must be called before using the client.

async shutdown() None[source]

Shuts the client down. Should be called before deconstructing the class.