dock_drive.hpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2012, Yujin Robot.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of Yujin Robot nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
35 /*****************************************************************************
36 ** Ifdefs
37 *****************************************************************************/
38 
39 #ifndef KOBUKI_DOCK_DRIVE_HPP_
40 #define KOBUKI_DOCK_DRIVE_HPP_
41 
42 /*****************************************************************************
43 ** Includes
44 *****************************************************************************/
45 
46 #include <iostream>
47 #include <sstream>
48 #include <iomanip>
49 #include <cmath>
50 #include <vector>
52 #include <ecl/linear_algebra.hpp>
53 
55 
56 /*****************************************************************************
57 ** Namespaces
58 *****************************************************************************/
59 
60 namespace kobuki {
61 
62 /*****************************************************************************
63 ** Interfaces
64 *****************************************************************************/
65 
66 class DockDrive {
67 public:
68  DockDrive();
69  ~DockDrive();
70 
71  bool init(){ return true; }
72  bool isEnabled() const { return is_enabled; }
73  bool canRun() const { return can_run; }
74 
75  void enable() { modeShift("enable"); }
76  void disable() { modeShift("disable"); }
77  void modeShift(const std::string& mode);
78 
79  void update(const std::vector<unsigned char> &signal /* dock_ir signal*/
80  , const unsigned char &bumper
81  , const unsigned char &charger
82  , const ecl::LegacyPose2D<double> &pose);
83 
84  void velocityCommands(const double &vx, const double &wz);
85 
86  /*********************
87  ** Command Accessors
88  **********************/
89  double getVX() const { return vx; }
90  double getWZ() const { return wz; }
91 
92  /*********************
93  ** Mode Accessors
94  **********************/
95  RobotDockingState::State getState() const { return state; }
96  std::string getStateStr() const { return state_str; }
97  std::string getDebugStr() const { return debug_str; }
98 
99  /*********************
100  ** Parameters Mutators
101  **********************/
102  void setMinAbsV(double mav) { min_abs_v = mav; }
103  void setMinAbsW(double maw) { min_abs_w = maw; }
104 
105  //debugging
106  std::string getDebugStream() { return debug_output; } //stream.str(); }
107  //std::string getDebugStream() { return debug_stream.str(); }
108  //std::ostringstream debug_stream;
109 
110  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
111 
112 protected:
113  void processBumpChargeEvent(const unsigned char& bumper, const unsigned char& charger);
115  void filterIRSensor(std::vector<unsigned char>& signal_filt,const std::vector<unsigned char> &signal );
116  void generateDebugMessage(const std::vector<unsigned char>& signal_filt, const unsigned char &bumper, const unsigned char &charger, const ecl::LegacyPose2D<double>& pose_update, const std::string& debug_str);
117  void updateVelocity(const std::vector<unsigned char>& signal_filt, const ecl::LegacyPose2D<double>& pose_update, std::string& debug_str);
118  RobotDockingState::State determineRobotLocation(const std::vector<unsigned char>& signal_filt,const unsigned char& charger);
119  bool validateSignal(const std::vector<unsigned char>& signal_filt, const unsigned int state);
120 
121 
122  // States
123  void idle(RobotDockingState::State& state,double& vx, double& wz);
124  void scan(RobotDockingState::State& state,double& vx, double& wz, const std::vector<unsigned char>& signal_filt, const ecl::LegacyPose2D<double>& pose_update, std::string& debug_str);
125  void find_stream(RobotDockingState::State& state,double& vx, double& wz, const std::vector<unsigned char>& signal_filt);
126  void get_stream(RobotDockingState::State& state,double& vx, double& wz, const std::vector<unsigned char>& signal_filt);
127  void aligned(RobotDockingState::State& state,double& vx, double& wz, const std::vector<unsigned char>& signal_filt, std::string& debug_str);
128  void bumped(RobotDockingState::State& nstate,double& nvx, double& nwz, int& bump_count);
129 
130 
131 private:
132  bool is_enabled, can_run;
133 
135  std::string state_str, debug_str;
136  double vx, wz;
137  std::vector<std::vector<unsigned char> > past_signals;
138  unsigned int signal_window;
139  int bump_remainder;
140  int dock_stabilizer;
141  int dock_detector;
142  double rotated;
143  double min_abs_v;
144  double min_abs_w;
146 
147  void setVel(double v, double w);
148 
149  std::string binary(unsigned char number) const;
150 
151  std::string debug_output;
152  std::vector<std::string> ROBOT_STATE_STR;
153 };
154 
155 } // namespace kobuki
156 
157 #endif /* KOBUKI_DOCK_DRIVE_HPP_ */
kobuki::DockDrive::canRun
bool canRun() const
Definition: dock_drive.hpp:87
kobuki::DockDrive::idle
void idle(RobotDockingState::State &state, double &vx, double &wz)
Definition: dock_drive_states.cpp:65
kobuki::DockDrive::binary
std::string binary(unsigned char number) const
Definition: dock_drive_debug.cpp:102
kobuki::DockDrive::DockDrive
DockDrive()
Definition: dock_drive.cpp:60
kobuki::DockDrive::bump_remainder
int bump_remainder
Definition: dock_drive.hpp:153
kobuki::DockDrive
Definition: dock_drive.hpp:72
kobuki::DockDrive::ROBOT_STATE_STR
std::vector< std::string > ROBOT_STATE_STR
Definition: dock_drive.hpp:166
kobuki
Definition: dock_drive.hpp:60
kobuki::DockDrive::setVel
void setVel(double v, double w)
Definition: dock_drive.cpp:92
kobuki::DockDrive::debug_output
std::string debug_output
Definition: dock_drive.hpp:165
kobuki::DockDrive::processBumpChargeEvent
void processBumpChargeEvent(const unsigned char &bumper, const unsigned char &charger)
Definition: dock_drive.cpp:201
kobuki::DockDrive::scan
void scan(RobotDockingState::State &state, double &vx, double &wz, const std::vector< unsigned char > &signal_filt, const ecl::LegacyPose2D< double > &pose_update, std::string &debug_str)
Definition: dock_drive_states.cpp:82
kobuki::DockDrive::get_stream
void get_stream(RobotDockingState::State &state, double &vx, double &wz, const std::vector< unsigned char > &signal_filt)
Definition: dock_drive_states.cpp:199
kobuki::DockDrive::signal_window
unsigned int signal_window
Definition: dock_drive.hpp:152
kobuki::DockDrive::state_str
std::string state_str
Definition: dock_drive.hpp:149
kobuki::DockDrive::getState
RobotDockingState::State getState() const
Definition: dock_drive.hpp:109
kobuki::DockDrive::init
bool init()
Definition: dock_drive.hpp:85
kobuki::DockDrive::debug_str
std::string debug_str
Definition: dock_drive.hpp:149
linear_algebra.hpp
ecl::LegacyPose2D< double >
kobuki::DockDrive::generateDebugMessage
void generateDebugMessage(const std::vector< unsigned char > &signal_filt, const unsigned char &bumper, const unsigned char &charger, const ecl::LegacyPose2D< double > &pose_update, const std::string &debug_str)
Definition: dock_drive_debug.cpp:50
kobuki::DockDrive::is_enabled
bool is_enabled
Definition: dock_drive.hpp:146
kobuki::DockDrive::getDebugStr
std::string getDebugStr() const
Definition: dock_drive.hpp:111
kobuki::DockDrive::updateVelocity
void updateVelocity(const std::vector< unsigned char > &signal_filt, const ecl::LegacyPose2D< double > &pose_update, std::string &debug_str)
Definition: dock_drive.cpp:241
kobuki::DockDrive::getDebugStream
std::string getDebugStream()
Definition: dock_drive.hpp:120
legacy_pose2d.hpp
kobuki::DockDrive::setMinAbsW
void setMinAbsW(double maw)
Definition: dock_drive.hpp:117
kobuki::DockDrive::determineRobotLocation
RobotDockingState::State determineRobotLocation(const std::vector< unsigned char > &signal_filt, const unsigned char &charger)
kobuki::DockDrive::past_signals
std::vector< std::vector< unsigned char > > past_signals
Definition: dock_drive.hpp:151
kobuki::DockDrive::vx
double vx
Definition: dock_drive.hpp:150
kobuki::DockDrive::setMinAbsV
void setMinAbsV(double mav)
Definition: dock_drive.hpp:116
kobuki::DockDrive::isEnabled
bool isEnabled() const
Definition: dock_drive.hpp:86
kobuki::DockDrive::getWZ
double getWZ() const
Definition: dock_drive.hpp:104
kobuki::DockDrive::find_stream
void find_stream(RobotDockingState::State &state, double &vx, double &wz, const std::vector< unsigned char > &signal_filt)
Definition: dock_drive_states.cpp:149
kobuki::DockDrive::enable
void enable()
Definition: dock_drive.hpp:89
kobuki::DockDrive::modeShift
void modeShift(const std::string &mode)
Definition: dock_drive.cpp:98
kobuki::DockDrive::rotated
double rotated
Definition: dock_drive.hpp:156
kobuki::DockDrive::velocityCommands
void velocityCommands(const double &vx, const double &wz)
Definition: dock_drive.cpp:187
kobuki::RobotDockingState::State
State
Definition: state.hpp:69
kobuki::DockDrive::~DockDrive
~DockDrive()
Definition: dock_drive.cpp:90
kobuki::DockDrive::wz
double wz
Definition: dock_drive.hpp:150
kobuki::DockDrive::update
void update(const std::vector< unsigned char > &signal, const unsigned char &bumper, const unsigned char &charger, const ecl::LegacyPose2D< double > &pose)
Updates the odometry from firmware stamps and encoders.
Definition: dock_drive.cpp:117
kobuki::DockDrive::disable
void disable()
Definition: dock_drive.hpp:90
kobuki::DockDrive::dock_detector
int dock_detector
Definition: dock_drive.hpp:155
kobuki::DockDrive::getStateStr
std::string getStateStr() const
Definition: dock_drive.hpp:110
kobuki::DockDrive::dock_stabilizer
int dock_stabilizer
Definition: dock_drive.hpp:154
state.hpp
States.
kobuki::DockDrive::bumped
void bumped(RobotDockingState::State &nstate, double &nvx, double &nwz, int &bump_count)
Definition: dock_drive_states.cpp:321
kobuki::DockDrive::can_run
bool can_run
Definition: dock_drive.hpp:146
kobuki::DockDrive::aligned
void aligned(RobotDockingState::State &state, double &vx, double &wz, const std::vector< unsigned char > &signal_filt, std::string &debug_str)
Definition: dock_drive_states.cpp:250
kobuki::DockDrive::pose_priv
ecl::LegacyPose2D< double > pose_priv
Definition: dock_drive.hpp:159
kobuki::DockDrive::getVX
double getVX() const
Definition: dock_drive.hpp:103
kobuki::DockDrive::filterIRSensor
void filterIRSensor(std::vector< unsigned char > &signal_filt, const std::vector< unsigned char > &signal)
Definition: dock_drive.cpp:170
kobuki::DockDrive::computePoseUpdate
void computePoseUpdate(ecl::LegacyPose2D< double > &pose_update, const ecl::LegacyPose2D< double > &pose)
compute pose update from previouse pose and current pose
Definition: dock_drive.cpp:151
kobuki::DockDrive::min_abs_v
double min_abs_v
Definition: dock_drive.hpp:157
kobuki::DockDrive::validateSignal
bool validateSignal(const std::vector< unsigned char > &signal_filt, const unsigned int state)
Definition: dock_drive.cpp:291
kobuki::DockDrive::state
RobotDockingState::State state
Definition: dock_drive.hpp:148
kobuki::DockDrive::min_abs_w
double min_abs_w
Definition: dock_drive.hpp:158


kobuki_dock_drive
Author(s): Younghun Ju
autogenerated on Wed Mar 2 2022 00:26:13