include
pr2_calibration_controllers
fake_calibration_controller.h
Go to the documentation of this file.
1
/*********************************************************************
2
* Software License Agreement (BSD License)
3
*
4
* Copyright (c) 2008, 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
35
#pragma once
36
37
#include <boost/scoped_ptr.hpp>
38
39
#include "
pr2_mechanism_model/robot.h
"
40
#include "
robot_mechanism_controllers/joint_velocity_controller.h
"
41
#include "
realtime_tools/realtime_publisher.h
"
42
#include "std_msgs/Empty.h"
43
#include "pr2_controllers_msgs/QueryCalibrationState.h"
44
45
namespace
controller
46
{
47
48
class
FakeCalibrationController :
public
pr2_controller_interface::Controller
49
{
50
public
:
51
FakeCalibrationController
();
52
~FakeCalibrationController
();
53
54
virtual
bool
init
(
pr2_mechanism_model::RobotState
*robot,
ros::NodeHandle
&n);
55
virtual
void
starting
();
56
virtual
void
update
();
57
58
bool
isCalibrated
(pr2_controllers_msgs::QueryCalibrationState::Request& req, pr2_controllers_msgs::QueryCalibrationState::Response& resp);
59
60
61
protected
:
62
63
ros::NodeHandle
node_
;
64
pr2_mechanism_model::RobotState
*
robot_
;
65
ros::Time
last_publish_time_
;
66
ros::ServiceServer
is_calibrated_srv_
;
67
boost::scoped_ptr<realtime_tools::RealtimePublisher<std_msgs::Empty> >
pub_calibrated_
;
68
69
pr2_mechanism_model::JointState
*
joint_
;
70
};
71
72
73
}
74
75
controller::FakeCalibrationController::update
virtual void update()
Definition:
fake_calibration_controller.cpp:99
realtime_publisher.h
pr2_mechanism_model::JointState
controller::FakeCalibrationController::FakeCalibrationController
FakeCalibrationController()
Definition:
fake_calibration_controller.cpp:47
controller::FakeCalibrationController::last_publish_time_
ros::Time last_publish_time_
Definition:
fake_calibration_controller.h:129
controller::FakeCalibrationController::isCalibrated
bool isCalibrated(pr2_controllers_msgs::QueryCalibrationState::Request &req, pr2_controllers_msgs::QueryCalibrationState::Response &resp)
Definition:
fake_calibration_controller.cpp:91
joint_velocity_controller.h
ros::ServiceServer
controller::FakeCalibrationController::robot_
pr2_mechanism_model::RobotState * robot_
Definition:
fake_calibration_controller.h:128
controller::FakeCalibrationController::node_
ros::NodeHandle node_
Definition:
fake_calibration_controller.h:127
controller
controller::FakeCalibrationController::init
virtual bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
Definition:
fake_calibration_controller.cpp:56
pr2_mechanism_model::RobotState
controller::FakeCalibrationController::~FakeCalibrationController
~FakeCalibrationController()
Definition:
fake_calibration_controller.cpp:52
controller::FakeCalibrationController::starting
virtual void starting()
Definition:
fake_calibration_controller.cpp:86
controller::FakeCalibrationController::pub_calibrated_
boost::scoped_ptr< realtime_tools::RealtimePublisher< std_msgs::Empty > > pub_calibrated_
Definition:
fake_calibration_controller.h:131
pr2_controller_interface::Controller
ros::Time
controller::FakeCalibrationController::joint_
pr2_mechanism_model::JointState * joint_
Definition:
fake_calibration_controller.h:133
controller::FakeCalibrationController::is_calibrated_srv_
ros::ServiceServer is_calibrated_srv_
Definition:
fake_calibration_controller.h:130
ros::NodeHandle
robot.h
pr2_calibration_controllers
Author(s): Stuart Glaser
autogenerated on Sat Nov 12 2022 03:33:28