remote_control.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017, PickNik Consulting
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the PickNik Consulting nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Dave Coleman <dave@picknik.ai>
36  Desc: Tool for creating break points and user verification points through
37  manipulation pipelines or other live robotitc tool.
38  Think GDB for robots, or like, a state machine.
39 */
40 
41 #pragma once
42 
43 // C++
44 #include <string>
45 
46 // ROS
47 #include <ros/ros.h>
48 #include <sensor_msgs/Joy.h>
49 
50 namespace rviz_visual_tools
51 {
52 typedef std::function<void(bool)> DisplayWaitingState;
53 
54 class RemoteControl
55 {
56 public:
60  explicit RemoteControl(const ros::NodeHandle& nh);
61 
65  void rvizDashboardCallback(const sensor_msgs::Joy::ConstPtr& msg);
66 
71  bool setReadyForNextStep();
72 
76  void setAutonomous(bool autonomous = true);
77  void setFullAutonomous(bool autonomous = true);
78 
83  bool getAutonomous();
85 
89  void setStop(bool stop = true);
90 
94  bool getStop();
95 
100  bool waitForNextStep(const std::string& caption = "go to next step");
101  bool waitForNextFullStep(const std::string& caption = "go to next full step");
102 
104  bool isWaiting()
105  {
106  return is_waiting_;
107  }
108 
109  void setDisplayWaitingState(DisplayWaitingState displayWaitingState)
110  {
111  displayWaitingState_ = displayWaitingState;
112  }
113 
114 private:
115  // A shared node handle
117 
118  // Short name for this class
119  std::string name_ = "remote_control";
120 
121  // Input
123 
124  // Debug interface
125  bool is_waiting_ = false;
126  bool next_step_ready_ = false;
127  bool autonomous_ = false;
128  bool full_autonomous_ = false;
129  bool stop_ = false;
130 
131  // Callback to visualize waiting state
133 }; // end class
134 
135 typedef std::shared_ptr<RemoteControl> RemoteControlPtr;
136 typedef std::shared_ptr<const RemoteControl> RemoteControlConstPtr;
137 
138 } // namespace rviz_visual_tools
rviz_visual_tools::RemoteControl::rvizDashboardCallback
void rvizDashboardCallback(const sensor_msgs::Joy::ConstPtr &msg)
Callback from ROS topic.
Definition: remote_control.cpp:65
rviz_visual_tools::DisplayWaitingState
std::function< void(bool)> DisplayWaitingState
Definition: remote_control.h:84
rviz_visual_tools::RemoteControl::getFullAutonomous
bool getFullAutonomous()
Definition: remote_control.cpp:133
rviz_visual_tools::RemoteControl::isWaiting
bool isWaiting()
Return true if debug interface is waiting for user input.
Definition: remote_control.h:136
ros.h
rviz_visual_tools::RemoteControl::next_step_ready_
bool next_step_ready_
Definition: remote_control.h:158
rviz_visual_tools::RemoteControl::nh_
ros::NodeHandle nh_
Definition: remote_control.h:148
rviz_visual_tools::RemoteControl::setReadyForNextStep
bool setReadyForNextStep()
Step to next step.
Definition: remote_control.cpp:89
rviz_visual_tools::RemoteControlPtr
std::shared_ptr< RemoteControl > RemoteControlPtr
Definition: remote_control.h:167
rviz_visual_tools
Definition: imarker_simple.h:55
rviz_visual_tools::RemoteControl::full_autonomous_
bool full_autonomous_
Definition: remote_control.h:160
rviz_visual_tools::RemoteControl::getStop
bool getStop()
See if we are in stop mode.
Definition: remote_control.cpp:123
rviz_visual_tools::RemoteControl::setStop
void setStop(bool stop=true)
Stop something in pipeline.
Definition: remote_control.cpp:113
rviz_visual_tools::RemoteControl::is_waiting_
bool is_waiting_
Definition: remote_control.h:157
rviz_visual_tools::RemoteControl::displayWaitingState_
DisplayWaitingState displayWaitingState_
Definition: remote_control.h:164
rviz_visual_tools::RemoteControl::setDisplayWaitingState
void setDisplayWaitingState(DisplayWaitingState displayWaitingState)
Definition: remote_control.h:141
rviz_visual_tools::RemoteControl::name_
std::string name_
Definition: remote_control.h:151
rviz_visual_tools::RemoteControl::waitForNextStep
bool waitForNextStep(const std::string &caption="go to next step")
Wait until user presses a button.
Definition: remote_control.cpp:138
rviz_visual_tools::RemoteControl::waitForNextFullStep
bool waitForNextFullStep(const std::string &caption="go to next full step")
Definition: remote_control.cpp:178
rviz_visual_tools::RemoteControl::RemoteControl
RemoteControl(const ros::NodeHandle &nh)
Constructor.
Definition: remote_control.cpp:53
rviz_visual_tools::RemoteControl::setFullAutonomous
void setFullAutonomous(bool autonomous=true)
Definition: remote_control.cpp:106
rviz_visual_tools::RemoteControl::setAutonomous
void setAutonomous(bool autonomous=true)
Enable autonomous mode.
Definition: remote_control.cpp:100
rviz_visual_tools::RemoteControl::rviz_dashboard_sub_
ros::Subscriber rviz_dashboard_sub_
Definition: remote_control.h:154
rviz_visual_tools::RemoteControl::getAutonomous
bool getAutonomous()
Get the autonomous mode.
Definition: remote_control.cpp:128
rviz_visual_tools::RemoteControlConstPtr
std::shared_ptr< const RemoteControl > RemoteControlConstPtr
Definition: remote_control.h:168
rviz_visual_tools::RemoteControl::stop_
bool stop_
Definition: remote_control.h:161
rviz_visual_tools::RemoteControl::autonomous_
bool autonomous_
Definition: remote_control.h:159
ros::NodeHandle
ros::Subscriber


rviz_visual_tools
Author(s): Dave Coleman
autogenerated on Wed Mar 2 2022 01:03:26