joint_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 #ifndef PR2_JOINT_CALIBRATION_CONTROLLER
36 #define PR2_JOINT_CALIBRATION_CONTROLLER
37 
38 #include <boost/scoped_ptr.hpp>
39 #include <boost/shared_ptr.hpp>
40 
41 #include "ros/node_handle.h"
45 #include "std_msgs/Empty.h"
46 #include "pr2_controllers_msgs/QueryCalibrationState.h"
47 
48 
49 namespace controller
50 {
51 
52 class JointCalibrationController : public pr2_controller_interface::Controller
53 {
54 public:
57 
58  virtual bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n);
59  virtual void starting();
60  virtual void update();
61 
62  bool isCalibrated(pr2_controllers_msgs::QueryCalibrationState::Request& req, pr2_controllers_msgs::QueryCalibrationState::Response& resp);
63 
64 
65 protected:
70  boost::scoped_ptr<realtime_tools::RealtimePublisher<std_msgs::Empty> > pub_calibrated_;
71 
73  int state_;
74  int countdown_;
75 
76  double search_velocity_;
77  double original_position_;
78 
82 
84 };
85 
86 }
87 
88 
89 #endif
controller::JointCalibrationController::original_position_
double original_position_
Definition: joint_calibration_controller.h:141
controller::JointCalibrationController::node_
ros::NodeHandle node_
Definition: joint_calibration_controller.h:131
realtime_publisher.h
node_handle.h
pr2_mechanism_model::JointState
controller::JointCalibrationController::BEGINNING
@ BEGINNING
Definition: joint_calibration_controller.h:136
boost::shared_ptr< pr2_mechanism_model::Transmission >
controller::JointCalibrationController::update
virtual void update()
Definition: joint_calibration_controller.cpp:200
joint_velocity_controller.h
controller::JointCalibrationController::vc_
controller::JointVelocityController vc_
Definition: joint_calibration_controller.h:147
controller::JointCalibrationController::robot_
pr2_mechanism_model::RobotState * robot_
Definition: joint_calibration_controller.h:130
controller::JointCalibrationController::CALIBRATED
@ CALIBRATED
Definition: joint_calibration_controller.h:136
controller::JointCalibrationController::JointCalibrationController
JointCalibrationController()
Definition: joint_calibration_controller.cpp:45
controller::JointCalibrationController::MOVING_TO_HIGH
@ MOVING_TO_HIGH
Definition: joint_calibration_controller.h:136
controller::JointCalibrationController::actuator_
pr2_hardware_interface::Actuator * actuator_
Definition: joint_calibration_controller.h:143
controller::JointCalibrationController::is_calibrated_srv_
ros::ServiceServer is_calibrated_srv_
Definition: joint_calibration_controller.h:133
ros::ServiceServer
controller::JointCalibrationController::countdown_
int countdown_
Definition: joint_calibration_controller.h:138
controller::JointCalibrationController::init
virtual bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
Definition: joint_calibration_controller.cpp:55
controller::JointCalibrationController::isCalibrated
bool isCalibrated(pr2_controllers_msgs::QueryCalibrationState::Request &req, pr2_controllers_msgs::QueryCalibrationState::Response &resp)
Definition: joint_calibration_controller.cpp:191
controller
pr2_mechanism_model::RobotState
controller::JointCalibrationController::starting
virtual void starting()
Definition: joint_calibration_controller.cpp:183
controller::JointCalibrationController::state_
int state_
Definition: joint_calibration_controller.h:137
pr2_controller_interface::Controller
controller::JointCalibrationController::search_velocity_
double search_velocity_
Definition: joint_calibration_controller.h:140
controller::JointCalibrationController::pub_calibrated_
boost::scoped_ptr< realtime_tools::RealtimePublisher< std_msgs::Empty > > pub_calibrated_
Definition: joint_calibration_controller.h:134
controller::JointCalibrationController::MOVING_TO_LOW
@ MOVING_TO_LOW
Definition: joint_calibration_controller.h:136
controller::JointVelocityController
controller::JointCalibrationController::~JointCalibrationController
virtual ~JointCalibrationController()
Definition: joint_calibration_controller.cpp:51
ros::Time
controller::JointCalibrationController::joint_
pr2_mechanism_model::JointState * joint_
Definition: joint_calibration_controller.h:144
controller::JointCalibrationController::last_publish_time_
ros::Time last_publish_time_
Definition: joint_calibration_controller.h:132
controller::JointCalibrationController::transmission_
boost::shared_ptr< pr2_mechanism_model::Transmission > transmission_
Definition: joint_calibration_controller.h:145
pr2_hardware_interface::Actuator
controller::JointCalibrationController::INITIALIZED
@ INITIALIZED
Definition: joint_calibration_controller.h:136
ros::NodeHandle
robot.h


pr2_calibration_controllers
Author(s): Stuart Glaser
autogenerated on Sat Nov 12 2022 03:33:28