Public Member Functions | |
BaseControllerNode (BaseDevice baseDevice, String vel_topic) | |
GraphName | getDefaultNodeName () |
void | onNewMessage (Twist twist) |
void | onShutdown (Node node) |
void | onShutdownComplete (Node node) |
void | onStart (ConnectedNode connectedNode) |
Package Attributes | |
Thread | baseControllerThread |
Private Member Functions | |
synchronized void | setTwistValues (double linearVelX, double angVelZ) |
Private Attributes | |
double | angVelZ = 0.0 |
final BaseDevice | baseDevice |
String | CMD_VEL_TOPIC |
double | linearVelX = 0.0 |
Static Private Attributes | |
static final Log | log = LogFactory.getLog(BaseControllerNode.class) |
Definition at line 36 of file BaseControllerNode.java.
com.github.c77.base_controller.BaseControllerNode.BaseControllerNode | ( | BaseDevice | baseDevice, |
String | vel_topic | ||
) | [inline] |
Creates a new base controller node that listens twists in a given topic. Usually this will be cmd_vel.
vel_topic,: | The topic in which to listen for twists. |
baseDevice,: | The base device that wants to be used (Kobuki, Create or Husky for now) |
Definition at line 56 of file BaseControllerNode.java.
GraphName com.github.c77.base_controller.BaseControllerNode.getDefaultNodeName | ( | ) | [inline] |
Definition at line 46 of file BaseControllerNode.java.
void com.github.c77.base_controller.BaseControllerNode.onNewMessage | ( | Twist | twist | ) | [inline] |
Callback from the subscriber to the CMD_VEL topic. This method is called each time a command velocity message is received
twist | The command velocity message received |
Definition at line 136 of file BaseControllerNode.java.
void com.github.c77.base_controller.BaseControllerNode.onShutdown | ( | Node | node | ) | [inline] |
Definition at line 112 of file BaseControllerNode.java.
void com.github.c77.base_controller.BaseControllerNode.onShutdownComplete | ( | Node | node | ) | [inline] |
Definition at line 118 of file BaseControllerNode.java.
void com.github.c77.base_controller.BaseControllerNode.onStart | ( | ConnectedNode | connectedNode | ) | [inline] |
Should be called to finish the node initialization. The base driver, already initialize should be provided to this method. This allows to defer the device creation to the moment Android gives the application the required USB permissions.
This thread decouples the receiving of messages via ROS Topics from the sending of messages to the base. Most bases require a continuous stream of messages to be sent. This code makes sure to keep sending messages to the base, repeating the previously received message if necessary, to keep a continuous stream going.
Definition at line 69 of file BaseControllerNode.java.
synchronized void com.github.c77.base_controller.BaseControllerNode.setTwistValues | ( | double | linearVelX, |
double | angVelZ | ||
) | [inline, private] |
Definition at line 123 of file BaseControllerNode.java.
double com.github.c77.base_controller.BaseControllerNode.angVelZ = 0.0 [private] |
Definition at line 39 of file BaseControllerNode.java.
Definition at line 43 of file BaseControllerNode.java.
Definition at line 37 of file BaseControllerNode.java.
String com.github.c77.base_controller.BaseControllerNode.CMD_VEL_TOPIC [private] |
Definition at line 40 of file BaseControllerNode.java.
double com.github.c77.base_controller.BaseControllerNode.linearVelX = 0.0 [private] |
Definition at line 38 of file BaseControllerNode.java.
final Log com.github.c77.base_controller.BaseControllerNode.log = LogFactory.getLog(BaseControllerNode.class) [static, private] |
Definition at line 42 of file BaseControllerNode.java.