Package edu.tufts.hrilab.ros2
Class Ros2Node
java.lang.Object
edu.tufts.hrilab.ros2.Ros2Node
- Direct Known Subclasses:
JRosClientNode
Todo: Remove service dependencies
-
Field Summary
FieldsModifier and TypeFieldDescriptionTracks all the services on this node, and their associated names //TODO: Make genericprotected static org.slf4j.Logger
protected Map<Ros2Publisher<?>,
Integer> Tracks all the publishers on this node, and their remaining iterations.Tracks all the services on this node, and their associated names //TODO: Make generic -
Constructor Summary
Constructors -
Method Summary
Modifier and TypeMethodDescriptionabstract <GOAL extends id.jrosmessages.Message,
RES extends id.jrosmessages.Message, DEF extends pinorobotics.jros2actionlib.actionlib_msgs.Action2Definition<GOAL, RES>>
voidabstract void
addAndStartPublisher
(Ros2Publisher<?> pub) Convenience method to add and start a publisher indefinitely.abstract void
addAndStartPublisher
(Ros2Publisher<?> pub, Integer iters) Conveinece method to add and start a publisher for the given number of iterations.abstract void
addAndStartSubscriber
(Ros2Subscriber<?> sub) Adds the specified subscriber to the node.abstract void
addPublisher
(Ros2Publisher<?> pub) 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>>
voidaddService
(DEF definition, String serviceName) Creates a service...abstract <GOAL extends id.jrosmessages.Message,
RES extends id.jrosmessages.Message>
REScallAction
(String actionName, GOAL goal) abstract <REQ extends id.jrosmessages.Message,
RES extends id.jrosmessages.Message>
REScallService
(String serviceName, REQ message) abstract void
createTf()
void
end()
Spins down the node.abstract javax.vecmath.Matrix4d
lookupTransform
(String from, String to) abstract void
oneTimePublish
(Ros2Publisher<?> pub) Convenience method to publish a message one time for a given publisher.abstract void
removePublisher
(Ros2Publisher<?> pub) Stops and removes the publisher from the node.abstract void
removeSubscriber
(Ros2Subscriber<?> sub) Removes the specified subscriber from the node.void
spin()
Spins the node up at the default rate of 1.void
Spins the node up at the specified rate.abstract void
startPublisher
(Ros2Publisher<?> pub) Starts publishing the specified publisher indefinitely (assuming node is spinning).abstract void
startPublisher
(Ros2Publisher<?> pub, Integer iters) Starts publishing the specified publisher for the given iterations (assuming node is pinning).abstract void
stopPublisher
(Ros2Publisher<?> pub) Stops the given publisher from publishing.
-
Field Details
-
log
protected static org.slf4j.Logger log -
publisherList
Tracks all the publishers on this node, and their remaining iterations. Value is -1 for indefinite iterations. -
serviceList
Tracks all the services on this node, and their associated names //TODO: Make generic -
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
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
Adds the specified subscriber to the node. Immediately starts listening.- Parameters:
sub
- Subscriber to add to the node.
-
removeSubscriber
Removes the specified subscriber from the node. TODO: Currently no jrosclient functionality for this.- Parameters:
sub
- Subscriber to remove from the node.
-
addPublisher
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
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
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 startediters
- Iterations the publisher publishes for
-
oneTimePublish
Convenience method to publish a message one time for a given publisher. Removed after use.- Parameters:
pub
- Publisher to publish once
-
addAndStartPublisher
Convenience method to add and start a publisher indefinitely.- Parameters:
pub
- Publisher to be added and started- See Also:
-
addAndStartPublisher
Conveinece method to add and start a publisher for the given number of iterations.- Parameters:
pub
- Publisher to be added and startediters
- Number of iterations to publish for- See Also:
-
stopPublisher
Stops the given publisher from publishing. Can be started again.- Parameters:
pub
- Publisher to be stopped.
-
removePublisher
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, void addServiceDEF extends pinorobotics.jrosservices.msgs.ServiceDefinition<REQ, RES>> (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
-
addAction
public abstract <GOAL extends id.jrosmessages.Message,RES extends id.jrosmessages.Message, void addActionDEF extends pinorobotics.jros2actionlib.actionlib_msgs.Action2Definition<GOAL, RES>> (DEF def, String actionName) -
callAction
public abstract <GOAL extends id.jrosmessages.Message,RES extends id.jrosmessages.Message> RES callAction(String actionName, GOAL goal)
-