#include <cb_ros_launch.hpp>
|
| CbRosLaunch () |
|
| CbRosLaunch (std::string package, std::string launchfile, RosLaunchMode) |
|
virtual | ~CbRosLaunch () |
|
template<typename TOrthogonal , typename TSourceObject > |
void | onOrthogonalAllocation () |
|
void | onEntry () override |
|
template<typename TOrthogonal , typename TSourceObject > |
void | onOrthogonalAllocation () |
|
virtual | ~SmaccAsyncClientBehavior () |
|
template<typename TCallback , typename T > |
boost::signals2::connection | onSuccess (TCallback callback, T *object) |
|
template<typename TCallback , typename T > |
boost::signals2::connection | onFinished (TCallback callback, T *object) |
|
template<typename TCallback , typename T > |
boost::signals2::connection | onFailure (TCallback callback, T *object) |
|
void | requestForceFinish () |
|
void | executeOnEntry () override |
|
void | executeOnExit () override |
|
void | waitOnEntryThread (bool requestFinish) |
|
template<typename TCallbackMethod , typename T > |
boost::signals2::connection | onSuccess (TCallbackMethod callback, T *object) |
|
template<typename TCallbackMethod , typename T > |
boost::signals2::connection | onFinished (TCallbackMethod callback, T *object) |
|
template<typename TCallbackMethod , typename T > |
boost::signals2::connection | onFailure (TCallbackMethod callback, T *object) |
|
| ISmaccClientBehavior () |
|
virtual | ~ISmaccClientBehavior () |
|
ISmaccStateMachine * | getStateMachine () |
|
std::string | getName () const |
|
template<typename SmaccClientType > |
void | requiresClient (SmaccClientType *&storage) |
|
template<typename SmaccComponentType > |
void | requiresComponent (SmaccComponentType *&storage, bool throwExceptionIfNotExist=false) |
|
virtual void | onExit () |
|
Definition at line 35 of file cb_ros_launch.hpp.
◆ CbRosLaunch() [1/2]
smacc2::client_behaviors::CbRosLaunch::CbRosLaunch |
( |
| ) |
|
Definition at line 28 of file cb_ros_launch.cpp.
32{
33}
std::optional< std::string > launchFileName_
std::optional< std::string > packageName_
RosLaunchMode launchMode_
@ LAUNCH_CLIENT_BEHAVIOR_LIFETIME
◆ CbRosLaunch() [2/2]
smacc2::client_behaviors::CbRosLaunch::CbRosLaunch |
( |
std::string |
package, |
|
|
std::string |
launchfile, |
|
|
RosLaunchMode |
launchmode |
|
) |
| |
◆ ~CbRosLaunch()
smacc2::client_behaviors::CbRosLaunch::~CbRosLaunch |
( |
| ) |
|
|
virtual |
◆ onEntry()
void smacc2::client_behaviors::CbRosLaunch::onEntry |
( |
| ) |
|
|
overridevirtual |
Reimplemented from smacc2::ISmaccClientBehavior.
Definition at line 48 of file cb_ros_launch.cpp.
49{
50 RCLCPP_INFO_STREAM(
getLogger(),
"[CbRosLaunch] OnEntry");
51
52 std::string packageName, launchFileName;
54 {
55 std::function<
bool()> breakfunction;
56
58 {
60 }
61 else
62 {
63 breakfunction = []() -> bool { return false; };
64 }
65
66 RCLCPP_INFO_STREAM(
69
72
75 else
77 }
78 else
79 {
80 RCLCPP_INFO_STREAM(
getLogger(),
"[CbRosLaunch] finding Ros Launch client");
81
84 {
85 RCLCPP_INFO_STREAM(
88
90 }
91 else
92 {
93 RCLCPP_ERROR(
95 "[CbRosLaunch] Inccorrect ros launch operation. No Ros Launch client specified neither "
96 "package/roslaunch file path.");
97 }
98 }
99}
virtual rclcpp::Logger getLogger() const
void requiresClient(SmaccClientType *&storage)
bool isShutdownRequested()
onEntry is executed in a new thread. However the current state cannot be left until the onEntry threa...
std::string launchFileName_
static std::future< std::string > executeRosLaunch(std::string packageName, std::string launchFilename, std::function< bool()> cancelCondition)
smacc2::client_bases::ClRosLaunch * client_
std::future< std::string > future_
static std::vector< std::future< std::string > > detached_futures_
References client_, detached_futures_, smacc2::client_bases::ClRosLaunch::executeRosLaunch(), future_, smacc2::ISmaccClientBehavior::getLogger(), smacc2::SmaccAsyncClientBehavior::isShutdownRequested(), smacc2::client_bases::ClRosLaunch::launch(), smacc2::client_behaviors::LAUNCH_CLIENT_BEHAVIOR_LIFETIME, smacc2::client_behaviors::LAUNCH_DETTACHED, smacc2::client_bases::ClRosLaunch::launchFileName_, launchFileName_, launchMode_, smacc2::client_bases::ClRosLaunch::packageName_, packageName_, and smacc2::ISmaccClientBehavior::requiresClient().
◆ onOrthogonalAllocation()
void smacc2::client_behaviors::CbRosLaunch::onOrthogonalAllocation |
( |
| ) |
|
|
inline |
Definition at line 50 of file cb_ros_launch.hpp.
51 {
52 smacc2::SmaccAsyncClientBehavior::onOrthogonalAllocation<TOrthogonal, TSourceObject>();
53 }
◆ client_
◆ detached_futures_
std::vector< std::future< std::string > > smacc2::client_behaviors::CbRosLaunch::detached_futures_ |
|
staticprivate |
◆ future_
std::future<std::string> smacc2::client_behaviors::CbRosLaunch::future_ |
|
protected |
◆ launchFileName_
std::optional<std::string> smacc2::client_behaviors::CbRosLaunch::launchFileName_ |
◆ launchMode_
◆ packageName_
std::optional<std::string> smacc2::client_behaviors::CbRosLaunch::packageName_ |
◆ result_
std::string smacc2::client_behaviors::CbRosLaunch::result_ |
|
protected |
The documentation for this class was generated from the following files: