sentry.h
Go to the documentation of this file.
1 /*******************************************************************************
2  * BSD 3-Clause License
3  *
4  * Copyright (c) 2021, Qiayuan Liao
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 are met:
9  *
10  * * Redistributions of source code must retain the above copyright notice, this
11  * list of conditions and the following disclaimer.
12  *
13  * * Redistributions in binary form must reproduce the above copyright notice,
14  * this list of conditions and the following disclaimer in the documentation
15  * and/or other materials provided with the distribution.
16  *
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived from
19  * this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
24  * ARE
25  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
26  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
27  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
28  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
30  * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
31  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
32  *******************************************************************************/
33 
34 //
35 // Created by flying on 2021/1/18.
36 //
37 
38 #pragma once
39 
42 
43 namespace rm_chassis_controllers
44 {
45 class SentryController : public ChassisBase<rm_control::RobotStateInterface, hardware_interface::EffortJointInterface>
46 {
47 public:
48  SentryController() = default;
59  bool init(hardware_interface::RobotHW* robot_hw, ros::NodeHandle& root_nh, ros::NodeHandle& controller_nh) override;
60 
61 private:
67  void moveJoint(const ros::Time& time, const ros::Duration& period) override;
68  void catapult(const ros::Time& time, const ros::Duration& period);
69  void normal(const ros::Time& time, const ros::Duration& period);
74  geometry_msgs::Twist odometry() override;
75 
78 
79  bool if_catapult_;
81  double catapult_angle_;
82  double vel_coff_;
83  double last_vel_cmd_{ 0. };
85  double lock_duratoin_;
86 };
87 
88 } // namespace rm_chassis_controllers
rm_chassis_controllers::SentryController::last_vel_cmd_
double last_vel_cmd_
Definition: sentry.h:145
chassis_base.h
rm_chassis_controllers::SentryController::catapult_angle_
double catapult_angle_
Definition: sentry.h:143
rm_chassis_controllers::SentryController::SentryController
SentryController()=default
rm_chassis_controllers::SentryController::lock_time_
ros::Time lock_time_
Definition: sentry.h:146
effort_controllers::JointVelocityController
rm_chassis_controllers::SentryController::catapult
void catapult(const ros::Time &time, const ros::Duration &period)
Definition: sentry.cpp:119
rm_chassis_controllers::SentryController::ctrl_wheel_
effort_controllers::JointVelocityController ctrl_wheel_
Definition: sentry.h:138
hardware_interface::RobotHW
rm_chassis_controllers::SentryController::init
bool init(hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh) override
Execute ChassisBase::init. Init necessary handles.
Definition: sentry.cpp:75
rm_chassis_controllers::SentryController::ctrl_catapult_joint_
effort_controllers::JointPositionController ctrl_catapult_joint_
Definition: sentry.h:139
joint_position_controller.h
effort_controllers::JointPositionController
ros::Time
rm_chassis_controllers::SentryController::odometry
geometry_msgs::Twist odometry() override
Calculate current linear_x according to current velocity.
Definition: sentry.cpp:139
rm_chassis_controllers::SentryController::vel_coff_
double vel_coff_
Definition: sentry.h:144
rm_chassis_controllers::SentryController::if_catapult_
bool if_catapult_
Definition: sentry.h:141
rm_chassis_controllers::SentryController::normal
void normal(const ros::Time &time, const ros::Duration &period)
Definition: sentry.cpp:146
ros::Duration
rm_chassis_controllers::SentryController::lock_duratoin_
double lock_duratoin_
Definition: sentry.h:147
rm_chassis_controllers::SentryController::moveJoint
void moveJoint(const ros::Time &time, const ros::Duration &period) override
Calculate correct command and set it to wheel.
Definition: sentry.cpp:95
rm_chassis_controllers::SentryController::catapult_initial_velocity_
double catapult_initial_velocity_
Definition: sentry.h:142
ros::NodeHandle
rm_chassis_controllers
Definition: balance.h:15


rm_chassis_controllers
Author(s): Qiayuan Liao
autogenerated on Sun May 4 2025 02:57:17