Main Page
Related Pages
Namespaces
Classes
Files
File List
File Members
include
joint_qualification_controllers
joint_limit_calibration_controller.h
Go to the documentation of this file.
1
/*********************************************************************
2
* Software License Agreement (BSD License)
3
*
4
* Copyright (c) 2009, Willow Garage, Inc.
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 Willow Garage 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
42
#ifndef JOINT_LIMIT_CALIBRATION_CONTROLLER
43
#define JOINT_LIMIT_CALIBRATION_CONTROLLER
44
45
#include "
ros/ros.h
"
46
#include "
pr2_mechanism_model/robot.h
"
47
#include "
robot_mechanism_controllers/joint_velocity_controller.h
"
48
#include "
realtime_tools/realtime_publisher.h
"
49
#include "std_msgs/Empty.h"
50
51
namespace
joint_qualification_controllers
52
{
53
54
class
JointLimitCalibrationController
:
public
pr2_controller_interface::Controller
55
{
56
public
:
57
JointLimitCalibrationController
();
58
virtual
~JointLimitCalibrationController
();
59
60
virtual
bool
init
(
pr2_mechanism_model::RobotState
*robot,
ros::NodeHandle
&n);
61
62
virtual
void
update
();
63
64
bool
calibrated
() {
return
state_
==
CALIBRATED
; }
65
void
beginCalibration
() {
66
if
(
state_
==
INITIALIZED
)
67
state_
=
BEGINNING
;
68
}
69
70
protected
:
71
pr2_mechanism_model::RobotState
*
robot_
;
72
ros::NodeHandle
node_
;
73
boost::scoped_ptr<realtime_tools::RealtimePublisher<std_msgs::Empty> >
pub_calibrated_
;
74
ros::Time
last_publish_time_
;
75
76
enum
{
INITIALIZED
,
BEGINNING
,
STARTING
,
STOPPING
,
CALIBRATED
};
77
int
state_
;
78
int
count_
;
79
int
stop_count_
;
80
81
double
search_velocity_
;
82
83
pr2_hardware_interface::Actuator
*
actuator_
;
84
pr2_mechanism_model::JointState
*
joint_
;
85
pr2_mechanism_model::Transmission
*
transmission_
;
86
87
controller::JointVelocityController
vc_
;
88
};
89
90
91
}
92
93
94
#endif //JOINT_LIMIT_CALIBRATION_CONTROLLER
joint_qualification_controllers::JointLimitCalibrationController::pub_calibrated_
boost::scoped_ptr< realtime_tools::RealtimePublisher< std_msgs::Empty > > pub_calibrated_
Definition:
joint_limit_calibration_controller.h:73
joint_qualification_controllers::JointLimitCalibrationController::update
virtual void update()
Definition:
joint_limit_calibration_controller.cpp:121
pr2_mechanism_model::JointState
ros::NodeHandle
joint_qualification_controllers::JointLimitCalibrationController::CALIBRATED
Definition:
joint_limit_calibration_controller.h:76
joint_velocity_controller.h
joint_qualification_controllers
Definition:
checkout_controller.h:60
joint_qualification_controllers::JointLimitCalibrationController::BEGINNING
Definition:
joint_limit_calibration_controller.h:76
ros::Time
joint_qualification_controllers::JointLimitCalibrationController::robot_
pr2_mechanism_model::RobotState * robot_
Definition:
joint_limit_calibration_controller.h:71
joint_qualification_controllers::JointLimitCalibrationController::STARTING
Definition:
joint_limit_calibration_controller.h:76
joint_qualification_controllers::JointLimitCalibrationController::search_velocity_
double search_velocity_
Definition:
joint_limit_calibration_controller.h:81
robot.h
joint_qualification_controllers::JointLimitCalibrationController::joint_
pr2_mechanism_model::JointState * joint_
Definition:
joint_limit_calibration_controller.h:84
joint_qualification_controllers::JointLimitCalibrationController::state_
int state_
Definition:
joint_limit_calibration_controller.h:77
joint_qualification_controllers::JointLimitCalibrationController::STOPPING
Definition:
joint_limit_calibration_controller.h:76
joint_qualification_controllers::JointLimitCalibrationController::JointLimitCalibrationController
JointLimitCalibrationController()
joint_qualification_controllers::JointLimitCalibrationController::calibrated
bool calibrated()
Definition:
joint_limit_calibration_controller.h:64
joint_qualification_controllers::JointLimitCalibrationController::init
virtual bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
Definition:
joint_limit_calibration_controller.cpp:56
realtime_publisher.h
joint_qualification_controllers::JointLimitCalibrationController::last_publish_time_
ros::Time last_publish_time_
Definition:
joint_limit_calibration_controller.h:74
joint_qualification_controllers::JointLimitCalibrationController::transmission_
pr2_mechanism_model::Transmission * transmission_
Definition:
joint_limit_calibration_controller.h:85
joint_qualification_controllers::JointLimitCalibrationController::count_
int count_
Definition:
joint_limit_calibration_controller.h:78
joint_qualification_controllers::JointLimitCalibrationController::~JointLimitCalibrationController
virtual ~JointLimitCalibrationController()
Definition:
joint_limit_calibration_controller.cpp:52
joint_qualification_controllers::JointLimitCalibrationController::vc_
controller::JointVelocityController vc_
Definition:
joint_limit_calibration_controller.h:87
joint_qualification_controllers::JointLimitCalibrationController::INITIALIZED
Definition:
joint_limit_calibration_controller.h:76
pr2_mechanism_model::RobotState
ros.h
joint_qualification_controllers::JointLimitCalibrationController::node_
ros::NodeHandle node_
Definition:
joint_limit_calibration_controller.h:72
pr2_controller_interface::Controller
pr2_hardware_interface::Actuator
controller::JointVelocityController
joint_qualification_controllers::JointLimitCalibrationController::stop_count_
int stop_count_
Definition:
joint_limit_calibration_controller.h:79
pr2_mechanism_model::Transmission
joint_qualification_controllers::JointLimitCalibrationController
Definition:
joint_limit_calibration_controller.h:54
joint_qualification_controllers::JointLimitCalibrationController::beginCalibration
void beginCalibration()
Definition:
joint_limit_calibration_controller.h:65
joint_qualification_controllers::JointLimitCalibrationController::actuator_
pr2_hardware_interface::Actuator * actuator_
Definition:
joint_limit_calibration_controller.h:83
joint_qualification_controllers
Author(s): Kevin Watts, Melonee Wise
autogenerated on Wed Jan 6 2021 03:39:12