Class Ros2Node

java.lang.Object
edu.tufts.hrilab.ros2.Ros2Node
Direct Known Subclasses:
JRosClientNode

public abstract class Ros2Node extends Object
Todo: Remove service dependencies
  • Field Summary

    Fields
    Modifier and Type
    Field
    Description
    protected Map<String,pinorobotics.jros2actionlib.JRos2ActionClient<?,?>>
    Tracks all the services on this node, and their associated names //TODO: Make generic
    protected static org.slf4j.Logger
     
    protected Map<Ros2Publisher<?>,Integer>
    Tracks all the publishers on this node, and their remaining iterations.
    protected Map<String,pinorobotics.jros2services.JRos2ServiceClient<?,?>>
    Tracks all the services on this node, and their associated names //TODO: Make generic
  • Constructor Summary

    Constructors
    Constructor
    Description
     
  • Method Summary

    Modifier and Type
    Method
    Description
    abstract <GOAL extends id.jrosmessages.Message, RES extends id.jrosmessages.Message, DEF extends pinorobotics.jros2actionlib.actionlib_msgs.Action2Definition<GOAL, RES>>
    void
    addAction(DEF def, String actionName)
     
    abstract void
    Convenience method to add and start a publisher indefinitely.
    abstract void
    Conveinece method to add and start a publisher for the given number of iterations.
    abstract void
    Adds the specified subscriber to the node.
    abstract void
    Adds the specified publisher to the node.
    abstract <REQ extends id.jrosmessages.Message, RES extends id.jrosmessages.Message, DEF extends pinorobotics.jrosservices.msgs.ServiceDefinition<REQ, RES>>
    void
    addService(DEF definition, String serviceName)
    Creates a service...
    abstract <GOAL extends id.jrosmessages.Message, RES extends id.jrosmessages.Message>
    RES
    callAction(String actionName, GOAL goal)
     
    abstract <REQ extends id.jrosmessages.Message, RES extends id.jrosmessages.Message>
    RES
    callService(String serviceName, REQ message)
     
    abstract void
     
    void
    end()
    Spins down the node.
    abstract javax.vecmath.Matrix4d
     
    abstract void
    Convenience method to publish a message one time for a given publisher.
    abstract void
    Stops and removes the publisher from the node.
    abstract void
    Removes the specified subscriber from the node.
    void
    Spins the node up at the default rate of 1.
    void
    spin(Integer rate)
    Spins the node up at the specified rate.
    abstract void
    Starts publishing the specified publisher indefinitely (assuming node is spinning).
    abstract void
    Starts publishing the specified publisher for the given iterations (assuming node is pinning).
    abstract void
    Stops the given publisher from publishing.

    Methods inherited from class java.lang.Object

    clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
  • Field Details

    • log

      protected static org.slf4j.Logger log
    • publisherList

      protected Map<Ros2Publisher<?>,Integer> publisherList
      Tracks all the publishers on this node, and their remaining iterations. Value is -1 for indefinite iterations.
    • serviceList

      protected Map<String,pinorobotics.jros2services.JRos2ServiceClient<?,?>> serviceList
      Tracks all the services on this node, and their associated names //TODO: Make generic
    • actionList

      protected Map<String,pinorobotics.jros2actionlib.JRos2ActionClient<?,?>> actionList
      Tracks all the services on this node, and their associated names //TODO: Make generic
  • Constructor Details

    • Ros2Node

      public Ros2Node()
  • Method Details

    • spin

      public void spin()
      Spins the node up at the default rate of 1.
      See Also:
    • spin

      public void spin(Integer rate)
      Spins the node up at the specified rate. All publishers publish at this rate.
      Parameters:
      rate - Rate at which publishers are published.
    • end

      public void end()
      Spins down the node. All publishers will stop publishing.
    • addAndStartSubscriber

      public abstract void addAndStartSubscriber(Ros2Subscriber<?> sub)
      Adds the specified subscriber to the node. Immediately starts listening.
      Parameters:
      sub - Subscriber to add to the node.
    • removeSubscriber

      public abstract void removeSubscriber(Ros2Subscriber<?> sub)
      Removes the specified subscriber from the node. TODO: Currently no jrosclient functionality for this.
      Parameters:
      sub - Subscriber to remove from the node.
    • addPublisher

      public abstract void addPublisher(Ros2Publisher<?> pub)
      Adds the specified publisher to the node. Does not start publishing until the publisher is started.
      Parameters:
      pub - Publisher to add to the node.
    • startPublisher

      public abstract void startPublisher(Ros2Publisher<?> pub)
      Starts publishing the specified publisher indefinitely (assuming node is spinning). The node must have been added to the node.
      Parameters:
      pub - Existing publisher to be started
    • startPublisher

      public abstract void startPublisher(Ros2Publisher<?> pub, Integer iters)
      Starts publishing the specified publisher for the given iterations (assuming node is pinning). The node must have been added to the node.
      Parameters:
      pub - Existing publisher to be started
      iters - Iterations the publisher publishes for
    • oneTimePublish

      public abstract void oneTimePublish(Ros2Publisher<?> pub)
      Convenience method to publish a message one time for a given publisher. Removed after use.
      Parameters:
      pub - Publisher to publish once
    • addAndStartPublisher

      public abstract void addAndStartPublisher(Ros2Publisher<?> pub)
      Convenience method to add and start a publisher indefinitely.
      Parameters:
      pub - Publisher to be added and started
      See Also:
    • addAndStartPublisher

      public abstract void addAndStartPublisher(Ros2Publisher<?> pub, Integer iters)
      Conveinece method to add and start a publisher for the given number of iterations.
      Parameters:
      pub - Publisher to be added and started
      iters - Number of iterations to publish for
      See Also:
    • stopPublisher

      public abstract void stopPublisher(Ros2Publisher<?> pub)
      Stops the given publisher from publishing. Can be started again.
      Parameters:
      pub - Publisher to be stopped.
    • removePublisher

      public abstract void removePublisher(Ros2Publisher<?> pub)
      Stops and removes the publisher from the node. must be re-added to start again.
      Parameters:
      pub - Publisher to be stopped and removed
    • addService

      public abstract <REQ extends id.jrosmessages.Message, RES extends id.jrosmessages.Message, DEF extends pinorobotics.jrosservices.msgs.ServiceDefinition<REQ, RES>> void addService(DEF definition, String serviceName)
      Creates a service... This is definition is a nightmare. Should we just let users make this manually?
      Type Parameters:
      REQ -
      RES -
      DEF -
      Parameters:
      definition -
    • callService

      public abstract <REQ extends id.jrosmessages.Message, RES extends id.jrosmessages.Message> RES callService(String serviceName, REQ message)
    • createTf

      public abstract void createTf()
    • lookupTransform

      public abstract javax.vecmath.Matrix4d lookupTransform(String from, String to)
    • addAction

      public abstract <GOAL extends id.jrosmessages.Message, RES extends id.jrosmessages.Message, DEF extends pinorobotics.jros2actionlib.actionlib_msgs.Action2Definition<GOAL, RES>> void addAction(DEF def, String actionName)
    • callAction

      public abstract <GOAL extends id.jrosmessages.Message, RES extends id.jrosmessages.Message> RES callAction(String actionName, GOAL goal)