SMACC
Loading...
Searching...
No Matches
Public Types | Public Member Functions | Static Public Member Functions | Static Public Attributes | Private Attributes | List of all members
cl_move_base_z::CostmapSwitch Class Reference

#include <cp_costmap_switch.h>

Inheritance diagram for cl_move_base_z::CostmapSwitch:
Inheritance graph
Collaboration diagram for cl_move_base_z::CostmapSwitch:
Collaboration graph

Public Types

enum class  StandardLayers { GLOBAL_OBSTACLES_LAYER = 0 , LOCAL_OBSTACLES_LAYER = 1 , GLOBAL_INFLATED_LAYER = 2 , LOCAL_INFLATED_LAYER = 3 }
 

Public Member Functions

 CostmapSwitch ()
 
virtual void onInitialize () override
 
bool exists (std::string layerName)
 
void enable (std::string layerName)
 
void enable (StandardLayers layerType)
 
void disable (std::string layerName)
 
void disable (StandardLayers layerType)
 
void registerProxyFromDynamicReconfigureServer (std::string costmapName, std::string enablePropertyName="enabled")
 
- Public Member Functions inherited from smacc::ISmaccComponent
 ISmaccComponent ()
 
virtual ~ISmaccComponent ()
 
virtual std::string getName () const
 

Static Public Member Functions

static std::string getStandardCostmapName (StandardLayers layertype)
 

Static Public Attributes

static std::array< std::string, 4 > layerNames
 

Private Attributes

std::map< std::string, std::shared_ptr< CostmapProxy > > costmapProxies
 
cl_move_base_z::ClMoveBaseZmoveBaseClient_
 

Additional Inherited Members

- Protected Member Functions inherited from smacc::ISmaccComponent
virtual void initialize (ISmaccClient *owner)
 
void setStateMachine (ISmaccStateMachine *stateMachine)
 
template<typename EventType >
void postEvent (const EventType &ev)
 
template<typename EventType >
void postEvent ()
 
template<typename TOrthogonal , typename TSourceObject >
void onOrthogonalAllocation ()
 
template<typename TComponent >
void requiresComponent (TComponent *&requiredComponentStorage)
 
template<typename TClient >
void requiresClient (TClient *&requiredClientStorage)
 
virtual void onInitialize ()
 
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)
 
- Protected Attributes inherited from smacc::ISmaccComponent
ISmaccStateMachinestateMachine_
 
ISmaccClientowner_
 

Detailed Description

Definition at line 24 of file cp_costmap_switch.h.

Member Enumeration Documentation

◆ StandardLayers

Enumerator
GLOBAL_OBSTACLES_LAYER 
LOCAL_OBSTACLES_LAYER 
GLOBAL_INFLATED_LAYER 
LOCAL_INFLATED_LAYER 

Definition at line 27 of file cp_costmap_switch.h.

Constructor & Destructor Documentation

◆ CostmapSwitch()

cl_move_base_z::CostmapSwitch::CostmapSwitch ( )

Definition at line 21 of file cp_costmap_switch.cpp.

22{
23}

Member Function Documentation

◆ disable() [1/2]

void cl_move_base_z::CostmapSwitch::disable ( StandardLayers  layerType)

Definition at line 92 of file cp_costmap_switch.cpp.

93{
94 this->disable(getStandardCostmapName(layerType));
95}
static std::string getStandardCostmapName(StandardLayers layertype)
void disable(std::string layerName)

References disable(), and getStandardCostmapName().

Here is the call graph for this function:

◆ disable() [2/2]

void cl_move_base_z::CostmapSwitch::disable ( std::string  layerName)

Definition at line 76 of file cp_costmap_switch.cpp.

77{
78 ROS_INFO("[CostmapSwitch] disabling %s", layerName.c_str());
79
80 if (!exists(layerName))
81 {
82 ROS_ERROR("[CostmapSwitch] costmap %s does not exist", layerName.c_str());
83 return;
84 }
85 else
86 {
87 ROS_INFO("[CostmapSwitch] costmap %s found. Calling dynamic reconfigure server.", layerName.c_str());
88 costmapProxies[layerName]->setCostmapEnabled(false);
89 }
90}
std::map< std::string, std::shared_ptr< CostmapProxy > > costmapProxies
bool exists(std::string layerName)

References costmapProxies, and exists().

Referenced by disable().

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

◆ enable() [1/2]

void cl_move_base_z::CostmapSwitch::enable ( StandardLayers  layerType)

Definition at line 71 of file cp_costmap_switch.cpp.

72{
73 this->enable(getStandardCostmapName(layerType));
74}
void enable(std::string layerName)

References enable(), and getStandardCostmapName().

Here is the call graph for this function:

◆ enable() [2/2]

void cl_move_base_z::CostmapSwitch::enable ( std::string  layerName)

Definition at line 55 of file cp_costmap_switch.cpp.

56{
57 ROS_INFO("[CostmapSwitch] enabling %s", layerName.c_str());
58
59 if (!exists(layerName))
60 {
61 ROS_ERROR("[CostmapSwitch] costmap %s does not exist", layerName.c_str());
62 return;
63 }
64 else
65 {
66 ROS_INFO("[CostmapSwitch] costmap %s found. Calling dynamic reconfigure server.", layerName.c_str());
67 costmapProxies[layerName]->setCostmapEnabled(true);
68 }
69}

References costmapProxies, and exists().

Referenced by enable().

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

◆ exists()

bool cl_move_base_z::CostmapSwitch::exists ( std::string  layerName)

Definition at line 45 of file cp_costmap_switch.cpp.

46{
47 if (!this->costmapProxies.count(layerName))
48 {
49 return false;
50 }
51
52 return true;
53}

References costmapProxies.

Referenced by disable(), and enable().

Here is the caller graph for this function:

◆ getStandardCostmapName()

std::string cl_move_base_z::CostmapSwitch::getStandardCostmapName ( StandardLayers  layertype)
static

Definition at line 40 of file cp_costmap_switch.cpp.

41{
42 return CostmapSwitch::layerNames[(int)layertype];
43}
static std::array< std::string, 4 > layerNames

References layerNames.

Referenced by disable(), enable(), and onInitialize().

Here is the caller graph for this function:

◆ onInitialize()

void cl_move_base_z::CostmapSwitch::onInitialize ( )
overridevirtual

Reimplemented from smacc::ISmaccComponent.

Definition at line 25 of file cp_costmap_switch.cpp.

References getStandardCostmapName(), GLOBAL_INFLATED_LAYER, GLOBAL_OBSTACLES_LAYER, LOCAL_INFLATED_LAYER, LOCAL_OBSTACLES_LAYER, moveBaseClient_, smacc::ISmaccComponent::owner_, and registerProxyFromDynamicReconfigureServer().

Here is the call graph for this function:

◆ registerProxyFromDynamicReconfigureServer()

void cl_move_base_z::CostmapSwitch::registerProxyFromDynamicReconfigureServer ( std::string  costmapName,
std::string  enablePropertyName = "enabled" 
)

Definition at line 14 of file cp_costmap_switch.cpp.

15{
16 ROS_INFO("[CostmapSwitch] registering costmap type: %s", costmapName.c_str());
17 auto proxy = std::make_shared<CostmapProxy>(this->moveBaseClient_->name_ + "/" + costmapName, enablePropertyName);
18 costmapProxies[costmapName] = proxy;
19}

References costmapProxies, moveBaseClient_, and smacc::client_bases::SmaccActionClientBase< ActionType >::name_.

Referenced by onInitialize().

Here is the caller graph for this function:

Member Data Documentation

◆ costmapProxies

std::map<std::string, std::shared_ptr<CostmapProxy> > cl_move_base_z::CostmapSwitch::costmapProxies
private

◆ layerNames

std::array< std::string, 4 > cl_move_base_z::CostmapSwitch::layerNames
static
Initial value:
=
{
"global_costmap/obstacles_layer",
"local_costmap/obstacles_layer"
"global_costmap/inflater_layer",
"local_costmap/inflater_layer"}

Definition at line 35 of file cp_costmap_switch.h.

Referenced by getStandardCostmapName().

◆ moveBaseClient_

cl_move_base_z::ClMoveBaseZ* cl_move_base_z::CostmapSwitch::moveBaseClient_
private

Definition at line 57 of file cp_costmap_switch.h.

Referenced by onInitialize(), and registerProxyFromDynamicReconfigureServer().


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