SMACC2
Loading...
Searching...
No Matches
cl_px4_mr::CpMicroRosAgent Class Reference

#include <cp_micro_ros_agent.hpp>

Inheritance diagram for cl_px4_mr::CpMicroRosAgent:
Inheritance graph
Collaboration diagram for cl_px4_mr::CpMicroRosAgent:
Collaboration graph

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< boollaunched_ {false}
 
std::atomic< boolshutdownRequested_ {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
 
ISmaccStateMachinegetStateMachine ()
 
- Protected Attributes inherited from smacc2::ISmaccComponent
ISmaccStateMachinestateMachine_
 
ISmaccClientowner_
 

Detailed Description

Definition at line 26 of file cp_micro_ros_agent.hpp.

Constructor & Destructor Documentation

◆ CpMicroRosAgent()

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.

33: command_(std::move(command)), nodeName_(std::move(nodeName))
34{
35}

◆ ~CpMicroRosAgent()

cl_px4_mr::CpMicroRosAgent::~CpMicroRosAgent ( )
virtual

Definition at line 37 of file cp_micro_ros_agent.cpp.

References shutdown().

Here is the call graph for this function:

Member Function Documentation

◆ getNodeName()

std::string cl_px4_mr::CpMicroRosAgent::getNodeName ( ) const

Definition at line 166 of file cp_micro_ros_agent.cpp.

166{ return nodeName_; }

References nodeName_.

Referenced by cl_px4_mr::CbConnectMicroRosAgent::onEntry().

Here is the caller graph for this function:

◆ getPid()

pid_t cl_px4_mr::CpMicroRosAgent::getPid ( ) const

Definition at line 160 of file cp_micro_ros_agent.cpp.

161{
162 std::lock_guard<std::mutex> lock(mutex_);
163 return agentPid_;
164}

References agentPid_, and mutex_.

◆ isLaunched()

bool cl_px4_mr::CpMicroRosAgent::isLaunched ( ) const

Definition at line 158 of file cp_micro_ros_agent.cpp.

158{ return launched_; }

References launched_.

Referenced by cl_px4_mr::CbConnectMicroRosAgent::onEntry().

Here is the caller graph for this function:

◆ killProcessesRecursive()

void cl_px4_mr::CpMicroRosAgent::killProcessesRecursive ( pid_t pid)
staticprivate

Definition at line 168 of file cp_micro_ros_agent.cpp.

169{
170 std::string command = "pgrep -P " + std::to_string(pid);
171 FILE * pipe = popen(command.c_str(), "r");
172
173 if (!pipe)
174 {
175 return;
176 }
177
178 char buffer[128];
179 std::string result;
180
181 while (fgets(buffer, sizeof(buffer), pipe) != NULL)
182 {
183 result += buffer;
184 }
185
186 pclose(pipe);
187
188 std::istringstream iss(result);
189 pid_t childPid;
190 std::vector<pid_t> childPids;
191
192 while (iss >> childPid)
193 {
194 childPids.push_back(childPid);
195 }
196
197 // Kill child processes before killing the parent process
198 for (const pid_t & child : childPids)
199 {
201 }
202
203 // After killing all children, kill the parent process
204 int res = kill(pid, SIGTERM);
205 if (res == 0)
206 {
207 RCLCPP_FATAL(rclcpp::get_logger("CpMicroRosAgent"), "Killed process %d", pid);
208 }
209}
static void killProcessesRecursive(pid_t pid)

References killProcessesRecursive().

Referenced by killProcessesRecursive(), and shutdown().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ launch()

void cl_px4_mr::CpMicroRosAgent::launch ( )

Definition at line 39 of file cp_micro_ros_agent.cpp.

40{
41 std::lock_guard<std::mutex> lock(mutex_);
42
43 if (launched_)
44 {
45 RCLCPP_INFO(getLogger(), "CpMicroRosAgent: already launched, skipping");
46 return;
47 }
48
49 RCLCPP_INFO(getLogger(), "CpMicroRosAgent: launching '%s'", command_.c_str());
50
51 int pipefd[2];
52 if (pipe(pipefd) == -1)
53 {
54 RCLCPP_ERROR(getLogger(), "CpMicroRosAgent: pipe() failed: %s", strerror(errno));
55 return;
56 }
57
58 pid_t pid = fork();
59
60 if (pid == 0)
61 {
62 // Child process
63 close(pipefd[0]);
64 dup2(pipefd[1], STDOUT_FILENO);
65 dup2(pipefd[1], STDERR_FILENO);
66 close(pipefd[1]);
67
68 execl("/bin/sh", "/bin/sh", "-c", command_.c_str(), nullptr);
69
70 // If execl returns, it failed
71 _exit(1);
72 }
73 else if (pid > 0)
74 {
75 // Parent process
76 close(pipefd[1]);
77 agentPid_ = pid;
78 pipeFd_ = pipefd[0];
79
80 // Set pipe to non-blocking
81 int flags = fcntl(pipeFd_, F_GETFL, 0);
82 fcntl(pipeFd_, F_SETFL, flags | O_NONBLOCK);
83
84 // Spawn detached reader thread to drain pipe (prevents buffer fill)
85 shutdownRequested_ = false;
86 std::thread readerThread(
87 [this]()
88 {
89 char buf[256];
90 while (!shutdownRequested_)
91 {
92 ssize_t n = read(pipeFd_, buf, sizeof(buf) - 1);
93 if (n > 0)
94 {
95 buf[n] = '\0';
96 RCLCPP_DEBUG(getLogger(), "[micro_ros_agent] %s", buf);
97 }
98 else
99 {
100 std::this_thread::sleep_for(std::chrono::milliseconds(100));
101 }
102 }
103 });
104 readerThread.detach();
105
106 launched_ = true;
107 RCLCPP_INFO(getLogger(), "CpMicroRosAgent: launched with PID %d", agentPid_);
108 }
109 else
110 {
111 RCLCPP_ERROR(getLogger(), "CpMicroRosAgent: fork() failed: %s", strerror(errno));
112 close(pipefd[0]);
113 close(pipefd[1]);
114 }
115}
std::atomic< bool > shutdownRequested_
rclcpp::Logger getLogger() const

References agentPid_, command_, smacc2::ISmaccComponent::getLogger(), launched_, mutex_, pipeFd_, and shutdownRequested_.

Referenced by cl_px4_mr::CbConnectMicroRosAgent::onEntry().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ shutdown()

void cl_px4_mr::CpMicroRosAgent::shutdown ( )

Definition at line 117 of file cp_micro_ros_agent.cpp.

118{
119 std::lock_guard<std::mutex> lock(mutex_);
120
121 if (agentPid_ <= 0)
122 {
123 return;
124 }
125
126 RCLCPP_INFO(getLogger(), "CpMicroRosAgent: shutting down agent (PID %d)", agentPid_);
127
128 shutdownRequested_ = true;
129
130 // Kill process tree recursively
132
133 // Reap zombie with brief retry loop
134 for (int i = 0; i < 10; i++)
135 {
136 int status;
137 pid_t result = waitpid(agentPid_, &status, WNOHANG);
138 if (result == agentPid_ || result == -1)
139 {
140 break;
141 }
142 std::this_thread::sleep_for(std::chrono::milliseconds(100));
143 }
144
145 // Close pipe
146 if (pipeFd_ >= 0)
147 {
148 close(pipeFd_);
149 pipeFd_ = -1;
150 }
151
152 agentPid_ = -1;
153 launched_ = false;
154
155 RCLCPP_INFO(getLogger(), "CpMicroRosAgent: shutdown complete");
156}

References agentPid_, smacc2::ISmaccComponent::getLogger(), killProcessesRecursive(), launched_, mutex_, pipeFd_, and shutdownRequested_.

Referenced by ~CpMicroRosAgent().

Here is the call graph for this function:
Here is the caller graph for this function:

Member Data Documentation

◆ agentPid_

pid_t cl_px4_mr::CpMicroRosAgent::agentPid_ = -1
private

Definition at line 44 of file cp_micro_ros_agent.hpp.

Referenced by getPid(), launch(), and shutdown().

◆ command_

std::string cl_px4_mr::CpMicroRosAgent::command_
private

Definition at line 47 of file cp_micro_ros_agent.hpp.

Referenced by launch().

◆ launched_

std::atomic<bool> cl_px4_mr::CpMicroRosAgent::launched_ {false}
private

Definition at line 45 of file cp_micro_ros_agent.hpp.

45{false};

Referenced by isLaunched(), launch(), and shutdown().

◆ mutex_

std::mutex cl_px4_mr::CpMicroRosAgent::mutex_
mutableprivate

Definition at line 49 of file cp_micro_ros_agent.hpp.

Referenced by getPid(), launch(), and shutdown().

◆ nodeName_

std::string cl_px4_mr::CpMicroRosAgent::nodeName_
private

Definition at line 48 of file cp_micro_ros_agent.hpp.

Referenced by getNodeName().

◆ pipeFd_

int cl_px4_mr::CpMicroRosAgent::pipeFd_ = -1
private

Definition at line 50 of file cp_micro_ros_agent.hpp.

Referenced by launch(), and shutdown().

◆ shutdownRequested_

std::atomic<bool> cl_px4_mr::CpMicroRosAgent::shutdownRequested_ {false}
private

Definition at line 46 of file cp_micro_ros_agent.hpp.

46{false};

Referenced by launch(), and shutdown().


The documentation for this class was generated from the following files: