#include <remote_control.h>
Definition at line 55 of file remote_control.h.
 
  
  | 
        
          | rviz_visual_tools::RemoteControl::RemoteControl | ( | const ros::NodeHandle & | nh | ) |  |  | explicit | 
 
 
      
        
          | 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.
 
 
      
        
          | bool rviz_visual_tools::RemoteControl::getFullAutonomous | ( |  | ) |  | 
      
 
 
      
        
          | bool rviz_visual_tools::RemoteControl::getStop | ( |  | ) |  | 
      
 
 
  
  | 
        
          | bool rviz_visual_tools::RemoteControl::isWaiting | ( |  | ) |  |  | inline | 
 
Return true if debug interface is waiting for user input. 
Definition at line 105 of file remote_control.h.
 
 
      
        
          | void rviz_visual_tools::RemoteControl::rvizDashboardCallback | ( | const sensor_msgs::Joy::ConstPtr & | msg | ) |  | 
      
 
 
      
        
          | void rviz_visual_tools::RemoteControl::setAutonomous | ( | bool | autonomous = true | ) |  | 
      
 
 
  
  | 
        
          | void rviz_visual_tools::RemoteControl::setDisplayWaitingState | ( | DisplayWaitingState | displayWaitingState | ) |  |  | inline | 
 
 
      
        
          | void rviz_visual_tools::RemoteControl::setFullAutonomous | ( | bool | autonomous = true | ) |  | 
      
 
 
      
        
          | bool rviz_visual_tools::RemoteControl::setReadyForNextStep | ( |  | ) |  | 
      
 
 
      
        
          | void rviz_visual_tools::RemoteControl::setStop | ( | bool | stop = true | ) |  | 
      
 
 
      
        
          | bool rviz_visual_tools::RemoteControl::waitForNextFullStep | ( | const std::string & | caption = "go to next full step" | ) |  | 
      
 
 
      
        
          | 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.
 
 
  
  | 
        
          | bool rviz_visual_tools::RemoteControl::autonomous_ = false |  | private | 
 
 
  
  | 
        
          | bool rviz_visual_tools::RemoteControl::full_autonomous_ = false |  | private | 
 
 
  
  | 
        
          | bool rviz_visual_tools::RemoteControl::is_waiting_ = false |  | private | 
 
 
  
  | 
        
          | std::string rviz_visual_tools::RemoteControl::name_ = "remote_control" |  | private | 
 
 
  
  | 
        
          | bool rviz_visual_tools::RemoteControl::next_step_ready_ = false |  | private | 
 
 
  
  | 
        
          | bool rviz_visual_tools::RemoteControl::stop_ = false |  | private | 
 
 
The documentation for this class was generated from the following files: