DiffDriverController.h
Go to the documentation of this file.
1 /******************************************************************************
2 *
3 * The MIT License (MIT)
4 *
5 * Copyright (c) 2018 Bluewhale Robot
6 *
7 * Permission is hereby granted, free of charge, to any person obtaining a copy
8 * of this software and associated documentation files (the "Software"), to deal
9 * in the Software without restriction, including without limitation the rights
10 * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
11 * copies of the Software, and to permit persons to whom the Software is
12 * furnished to do so, subject to the following conditions:
13 *
14 * The above copyright notice and this permission notice shall be included in all
15 * copies or substantial portions of the Software.
16 *
17 * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
18 * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
19 * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
20 * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
21 * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
22 * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
23 * SOFTWARE.
24 *
25 * Author: Xie fusheng
26 * Randoms
27 *******************************************************************************/
28 
29 #ifndef DIFFDRIVERCONTROLLER_H
30 #define DIFFDRIVERCONTROLLER_H
31 #include <ros/ros.h>
32 #include <std_msgs/Bool.h>
35 
37 {
39 {
40 public:
42  DiffDriverController(double max_speed_, std::string cmd_topic_, StatusPublisher* xq_status_,
43  CallbackAsyncSerial* cmd_serial_);
44  void run();
45  void sendcmd(const geometry_msgs::Twist& command);
46  void imuCalibration(const std_msgs::Bool& calFlag);
48  void updateMoveFlag(const std_msgs::Bool& moveFlag);
49  void updateBarDetectFlag(const std_msgs::Bool& DetectFlag);
50 
51 private:
52  double max_wheelspeed; //单位为转每秒,只能为正数
53  std::string cmd_topic;
56  boost::mutex mMutex;
57  bool MoveFlag;
58 };
59 }
60 #endif // DIFFDRIVERCONTROLLER_H
void updateMoveFlag(const std_msgs::Bool &moveFlag)
void setStatusPtr(StatusPublisher &status)
ROSLIB_DECL std::string command(const std::string &cmd)
void sendcmd(const geometry_msgs::Twist &command)
void updateBarDetectFlag(const std_msgs::Bool &DetectFlag)
void imuCalibration(const std_msgs::Bool &calFlag)


xiaoqiang_driver
Author(s): Xie fusheng
autogenerated on Mon Jun 10 2019 15:53:12