Internals

Controller node

This Python module implements a controller interface for interrupting the flow of geometry_msgs/Twist commands to the robot base.

class stop_base.controller_node.ControllerNode[source]

Stop base controller node.

lock = None

Big controller lock.

state = None

Current controller state.

last_command = None

Last velocity command received.

cmd_vel_callback(msg)[source]

Velocity command request callback.

Parameters:msg (geometry_msgs/Twist) – newest cmd_vel message.
stop_base_service(req)[source]

Service call to pause and resume robot base motion.

Parameters:req (bwi_msgs/StopBaseRequest) – service request message.
Returns:bwi_msgs/StopBaseResponse
stop_robot()[source]

Send stop commands to a robot not in the RUNNING state.

This implementation sends zero velocities at once. Some robots might benefit from more gradual stop velocities.

stop_base.controller_node.main()[source]

Controller node main entry point.

Service interface

This Python module provides interfaces for StopBase service calls.

stop_base.service.make_request(status, requester)[source]

Make a stop base service request.

Parameters:
  • status (int) – Requested status.
  • requester (str) – Requester name.
Returns:

bwi_msgs/StopBaseRequest message.

stop_base.service.make_response(status)[source]

Make a stop base service response.

Parameters:status (int) – Requested status.
Returns:bwi_msgs/StopBaseResponse message.
class stop_base.service.StopBaseClient(srv_name='stop_base')[source]

Proxy class for making stop_base calls.

stop_base(status, requester)[source]

Stop base service proxy.

Parameters:
  • status (int) – Requested status.
  • requester (str) – Requester name.
Returns:

bwi_msgs/StopBaseResponse message.

State transitions

This module tracks stop base request state transitions. The initial state is RUNNING, and the terminal state is STOPPED.

digraph state_transitions {
   RUNNING [peripheries=2]
   PAUSED [style="filled", color="grey"]
   STOPPED [peripheries=2, style="filled", color="grey"]
   RUNNING -> PAUSED
   RUNNING -> STOPPED
   PAUSED -> RUNNING
   PAUSED -> STOPPED
}

class stop_base.transitions.StopBaseState[source]

Class for tracking the status of a stop base request.

str(status)
Returns:String representation of this status.
status = None

Current status.

pauses = None

Set of pause requester names.

to_msg()[source]
Returns:corresponding bwi_msgs/StopBaseStatus message.
transition(msg)[source]

Update status based on this request message.

Parameters:msg (bwi_msgs/StopBaseRequest) – stop base service request message.
Raises:TransitionError if not a valid transition.
valid(new_status)[source]

Valid state update predicate.

Parameters:new_status – Proposed new status for this request.
Returns:True if this is a valid state transition.

Exceptions

This module defines exceptions raised by this package.

These exception names are all included in the main concert_scheduler_requests namespace. To catch one, import it this way:

from stop_base import TransitionError
exception stop_base.exceptions.TransitionError[source]

Error exception: invalid state transition.

Table Of Contents

Previous topic

Overview

Next topic

Change history

This Page