#include <remote_control.h>
Definition at line 86 of file remote_control.h.
 
◆ RemoteControl()
  
  
      
        
          | rviz_visual_tools::RemoteControl::RemoteControl  | 
          ( | 
          const ros::NodeHandle &  | 
          nh | ) | 
           | 
         
       
   | 
  
explicit   | 
  
 
 
◆ getAutonomous()
      
        
          | bool rviz_visual_tools::RemoteControl::getAutonomous  | 
          ( | 
           | ) | 
           | 
        
      
 
Get the autonomous mode. 
- Returns
 - true if is in autonomous mode 
 
Definition at line 128 of file remote_control.cpp.
 
 
◆ getFullAutonomous()
      
        
          | bool rviz_visual_tools::RemoteControl::getFullAutonomous  | 
          ( | 
           | ) | 
           | 
        
      
 
 
◆ getStop()
      
        
          | bool rviz_visual_tools::RemoteControl::getStop  | 
          ( | 
           | ) | 
           | 
        
      
 
 
◆ isWaiting()
  
  
      
        
          | bool rviz_visual_tools::RemoteControl::isWaiting  | 
          ( | 
           | ) | 
           | 
         
       
   | 
  
inline   | 
  
 
Return true if debug interface is waiting for user input. 
Definition at line 136 of file remote_control.h.
 
 
◆ rvizDashboardCallback()
      
        
          | void rviz_visual_tools::RemoteControl::rvizDashboardCallback  | 
          ( | 
          const sensor_msgs::Joy::ConstPtr &  | 
          msg | ) | 
           | 
        
      
 
 
◆ setAutonomous()
      
        
          | void rviz_visual_tools::RemoteControl::setAutonomous  | 
          ( | 
          bool  | 
          autonomous = true | ) | 
           | 
        
      
 
 
◆ setDisplayWaitingState()
  
  
      
        
          | void rviz_visual_tools::RemoteControl::setDisplayWaitingState  | 
          ( | 
          DisplayWaitingState  | 
          displayWaitingState | ) | 
           | 
         
       
   | 
  
inline   | 
  
 
 
◆ setFullAutonomous()
      
        
          | void rviz_visual_tools::RemoteControl::setFullAutonomous  | 
          ( | 
          bool  | 
          autonomous = true | ) | 
           | 
        
      
 
 
◆ setReadyForNextStep()
      
        
          | bool rviz_visual_tools::RemoteControl::setReadyForNextStep  | 
          ( | 
           | ) | 
           | 
        
      
 
 
◆ setStop()
      
        
          | void rviz_visual_tools::RemoteControl::setStop  | 
          ( | 
          bool  | 
          stop = true | ) | 
           | 
        
      
 
 
◆ waitForNextFullStep()
      
        
          | bool rviz_visual_tools::RemoteControl::waitForNextFullStep  | 
          ( | 
          const std::string &  | 
          caption = "go to next full step" | ) | 
           | 
        
      
 
 
◆ waitForNextStep()
      
        
          | bool rviz_visual_tools::RemoteControl::waitForNextStep  | 
          ( | 
          const std::string &  | 
          caption = "go to next step" | ) | 
           | 
        
      
 
Wait until user presses a button. 
- Returns
 - true on success 
 
Definition at line 138 of file remote_control.cpp.
 
 
◆ autonomous_
  
  
      
        
          | bool rviz_visual_tools::RemoteControl::autonomous_ = false | 
         
       
   | 
  
private   | 
  
 
 
◆ displayWaitingState_
◆ full_autonomous_
  
  
      
        
          | bool rviz_visual_tools::RemoteControl::full_autonomous_ = false | 
         
       
   | 
  
private   | 
  
 
 
◆ is_waiting_
  
  
      
        
          | bool rviz_visual_tools::RemoteControl::is_waiting_ = false | 
         
       
   | 
  
private   | 
  
 
 
◆ name_
  
  
      
        
          | std::string rviz_visual_tools::RemoteControl::name_ = "remote_control" | 
         
       
   | 
  
private   | 
  
 
 
◆ next_step_ready_
  
  
      
        
          | bool rviz_visual_tools::RemoteControl::next_step_ready_ = false | 
         
       
   | 
  
private   | 
  
 
 
◆ nh_
◆ rviz_dashboard_sub_
◆ stop_
  
  
      
        
          | bool rviz_visual_tools::RemoteControl::stop_ = false | 
         
       
   | 
  
private   | 
  
 
 
The documentation for this class was generated from the following files: