|
SMACC2
|
#include <cp_micro_ros_agent.hpp>


Public Member Functions | |
| CpMicroRosAgent (std::string command="ros2 run micro_ros_agent micro_ros_agent udp4 -p 8888 2>&1 | tee /tmp/xrce_agent.log", std::string nodeName="/px4_micro_xrce_dds") | |
| virtual | ~CpMicroRosAgent () |
| void | launch () |
| void | shutdown () |
| bool | isLaunched () const |
| pid_t | getPid () const |
| std::string | getNodeName () const |
Public Member Functions inherited from smacc2::ISmaccComponent | |
| ISmaccComponent () | |
| virtual | ~ISmaccComponent () |
| virtual std::string | getName () const |
Static Private Member Functions | |
| static void | killProcessesRecursive (pid_t pid) |
Private Attributes | |
| pid_t | agentPid_ = -1 |
| std::atomic< bool > | launched_ {false} |
| std::atomic< bool > | shutdownRequested_ {false} |
| std::string | command_ |
| std::string | nodeName_ |
| std::mutex | mutex_ |
| int | pipeFd_ = -1 |
Additional Inherited Members | |
Protected Member Functions inherited from smacc2::ISmaccComponent | |
| virtual void | onInitialize () |
| template<typename TOrthogonal , typename TClient > | |
| void | onComponentInitialization () |
| template<typename EventType > | |
| void | postEvent (const EventType &ev) |
| template<typename EventType > | |
| void | postEvent () |
| template<typename TOrthogonal , typename TSourceObject > | |
| void | onStateOrthogonalAllocation () |
| template<typename TComponent > | |
| void | requiresComponent (TComponent *&requiredComponentStorage, ComponentRequirement requirementType=ComponentRequirement::SOFT) |
| template<typename TComponent > | |
| void | requiresComponent (std::string name, TComponent *&requiredComponentStorage, ComponentRequirement requirementType=ComponentRequirement::SOFT) |
| template<typename TClient > | |
| void | requiresClient (TClient *&requiredClientStorage) |
| template<typename SmaccComponentType , typename TOrthogonal , typename TClient , typename... TArgs> | |
| SmaccComponentType * | createSiblingComponent (TArgs... targs) |
| template<typename SmaccComponentType , typename TOrthogonal , typename TClient , typename... TArgs> | |
| SmaccComponentType * | createSiblingNamedComponent (std::string name, TArgs... targs) |
| rclcpp::Node::SharedPtr | getNode () |
| rclcpp::Logger | getLogger () const |
| ISmaccStateMachine * | getStateMachine () |
Protected Attributes inherited from smacc2::ISmaccComponent | |
| ISmaccStateMachine * | stateMachine_ |
| ISmaccClient * | owner_ |
Definition at line 26 of file cp_micro_ros_agent.hpp.
| cl_px4_mr::CpMicroRosAgent::CpMicroRosAgent | ( | std::string | command = "ros2 run micro_ros_agent micro_ros_agent udp4 -p 8888 2>&1 | tee /tmp/xrce_agent.log", |
| std::string | nodeName = "/px4_micro_xrce_dds" ) |
Definition at line 32 of file cp_micro_ros_agent.cpp.
|
virtual |
Definition at line 37 of file cp_micro_ros_agent.cpp.
References shutdown().

| std::string cl_px4_mr::CpMicroRosAgent::getNodeName | ( | ) | const |
Definition at line 166 of file cp_micro_ros_agent.cpp.
References nodeName_.
Referenced by cl_px4_mr::CbConnectMicroRosAgent::onEntry().

| pid_t cl_px4_mr::CpMicroRosAgent::getPid | ( | ) | const |
Definition at line 160 of file cp_micro_ros_agent.cpp.
| bool cl_px4_mr::CpMicroRosAgent::isLaunched | ( | ) | const |
Definition at line 158 of file cp_micro_ros_agent.cpp.
References launched_.
Referenced by cl_px4_mr::CbConnectMicroRosAgent::onEntry().

|
staticprivate |
Definition at line 168 of file cp_micro_ros_agent.cpp.
References killProcessesRecursive().
Referenced by killProcessesRecursive(), and shutdown().


| void cl_px4_mr::CpMicroRosAgent::launch | ( | ) |
Definition at line 39 of file cp_micro_ros_agent.cpp.
References agentPid_, command_, smacc2::ISmaccComponent::getLogger(), launched_, mutex_, pipeFd_, and shutdownRequested_.
Referenced by cl_px4_mr::CbConnectMicroRosAgent::onEntry().


| void cl_px4_mr::CpMicroRosAgent::shutdown | ( | ) |
Definition at line 117 of file cp_micro_ros_agent.cpp.
References agentPid_, smacc2::ISmaccComponent::getLogger(), killProcessesRecursive(), launched_, mutex_, pipeFd_, and shutdownRequested_.
Referenced by ~CpMicroRosAgent().


|
private |
Definition at line 44 of file cp_micro_ros_agent.hpp.
Referenced by getPid(), launch(), and shutdown().
|
private |
Definition at line 47 of file cp_micro_ros_agent.hpp.
Referenced by launch().
|
private |
Definition at line 45 of file cp_micro_ros_agent.hpp.
Referenced by isLaunched(), launch(), and shutdown().
|
mutableprivate |
Definition at line 49 of file cp_micro_ros_agent.hpp.
Referenced by getPid(), launch(), and shutdown().
|
private |
Definition at line 48 of file cp_micro_ros_agent.hpp.
Referenced by getNodeName().
|
private |
Definition at line 50 of file cp_micro_ros_agent.hpp.
Referenced by launch(), and shutdown().
|
private |
Definition at line 46 of file cp_micro_ros_agent.hpp.
Referenced by launch(), and shutdown().