gripper_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 
42 #include "std_msgs/Empty.h"
43 #include "pr2_controllers_msgs/QueryCalibrationState.h"
44 
45 namespace controller
46 {
47 
48 class GripperCalibrationController : public pr2_controller_interface::Controller
49 {
50 public:
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 
64  int state_;
65  int count_;
66  int stop_count_;
67 
72  boost::scoped_ptr<realtime_tools::RealtimePublisher<std_msgs::Empty> > pub_calibrated_;
73 
74  double search_velocity_;
77  std::vector<pr2_mechanism_model::JointState*> other_joints_;
78 
79  double init_time;
81 
83 };
84 
85 
86 }
87 
88 
realtime_publisher.h
pr2_mechanism_model::JointState
controller::GripperCalibrationController::robot_
pr2_mechanism_model::RobotState * robot_
Definition: gripper_calibration_controller.h:133
controller::GripperCalibrationController::search_velocity_
double search_velocity_
Definition: gripper_calibration_controller.h:138
controller::GripperCalibrationController::joint_
pr2_mechanism_model::JointState * joint_
Definition: gripper_calibration_controller.h:140
joint_velocity_controller.h
controller::GripperCalibrationController::init_time
double init_time
Definition: gripper_calibration_controller.h:143
controller::GripperCalibrationController::STARTING
@ STARTING
Definition: gripper_calibration_controller.h:127
controller::GripperCalibrationController::other_joints_
std::vector< pr2_mechanism_model::JointState * > other_joints_
Definition: gripper_calibration_controller.h:141
controller::GripperCalibrationController::GripperCalibrationController
GripperCalibrationController()
Definition: gripper_calibration_controller.cpp:47
controller::GripperCalibrationController::INITIALIZED
@ INITIALIZED
Definition: gripper_calibration_controller.h:127
ros::ServiceServer
controller::GripperCalibrationController::is_calibrated_srv_
ros::ServiceServer is_calibrated_srv_
Definition: gripper_calibration_controller.h:135
controller::GripperCalibrationController::CALIBRATED
@ CALIBRATED
Definition: gripper_calibration_controller.h:127
controller::GripperCalibrationController::node_
ros::NodeHandle node_
Definition: gripper_calibration_controller.h:132
controller::GripperCalibrationController::isCalibrated
bool isCalibrated(pr2_controllers_msgs::QueryCalibrationState::Request &req, pr2_controllers_msgs::QueryCalibrationState::Response &resp)
Definition: gripper_calibration_controller.cpp:168
controller::GripperCalibrationController::vc_
controller::JointVelocityController vc_
Definition: gripper_calibration_controller.h:146
controller
pr2_mechanism_model::RobotState
controller::GripperCalibrationController::stopped_velocity_tolerance_
double stopped_velocity_tolerance_
Definition: gripper_calibration_controller.h:144
controller::GripperCalibrationController::stop_count_
int stop_count_
Definition: gripper_calibration_controller.h:130
pr2_controller_interface::Controller
controller::JointVelocityController
controller::GripperCalibrationController::pub_calibrated_
boost::scoped_ptr< realtime_tools::RealtimePublisher< std_msgs::Empty > > pub_calibrated_
Definition: gripper_calibration_controller.h:136
controller::GripperCalibrationController::~GripperCalibrationController
~GripperCalibrationController()
Definition: gripper_calibration_controller.cpp:52
controller::GripperCalibrationController::CLOSING_SLOWLY
@ CLOSING_SLOWLY
Definition: gripper_calibration_controller.h:127
controller::GripperCalibrationController::init
virtual bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
Definition: gripper_calibration_controller.cpp:56
ros::Time
controller::GripperCalibrationController::starting
virtual void starting()
Definition: gripper_calibration_controller.cpp:160
controller::GripperCalibrationController::update
virtual void update()
Definition: gripper_calibration_controller.cpp:176
controller::GripperCalibrationController::actuator_
pr2_hardware_interface::Actuator * actuator_
Definition: gripper_calibration_controller.h:139
controller::GripperCalibrationController::count_
int count_
Definition: gripper_calibration_controller.h:129
controller::GripperCalibrationController::last_publish_time_
ros::Time last_publish_time_
Definition: gripper_calibration_controller.h:134
controller::GripperCalibrationController::BEGINNING
@ BEGINNING
Definition: gripper_calibration_controller.h:127
pr2_hardware_interface::Actuator
controller::GripperCalibrationController::state_
int state_
Definition: gripper_calibration_controller.h:128
controller::GripperCalibrationController::BACK_OFF
@ BACK_OFF
Definition: gripper_calibration_controller.h:127
controller::GripperCalibrationController::CLOSING
@ CLOSING
Definition: gripper_calibration_controller.h:127
ros::NodeHandle
robot.h


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