Main Page
Namespaces
Classes
Files
File List
include
robot_mechanism_controllers
cartesian_wrench_controller.h
Go to the documentation of this file.
1
/*
2
* Copyright (c) 2008, Willow Garage, Inc.
3
* All rights reserved.
4
*
5
* Redistribution and use in source and binary forms, with or without
6
* modification, are permitted provided that the following conditions are met:
7
*
8
* * Redistributions of source code must retain the above copyright
9
* notice, this list of conditions and the following disclaimer.
10
* * Redistributions in binary form must reproduce the above copyright
11
* notice, this list of conditions and the following disclaimer in the
12
* documentation and/or other materials provided with the distribution.
13
* * Neither the name of the Willow Garage, Inc. nor the names of its
14
* contributors may be used to endorse or promote products derived from
15
* this software without specific prior written permission.
16
*
17
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27
* POSSIBILITY OF SUCH DAMAGE.
28
*/
29
54
#ifndef CARTESIAN_WRENCH_CONTROLLER_H
55
#define CARTESIAN_WRENCH_CONTROLLER_H
56
57
#include <vector>
58
#include <kdl/chain.hpp>
59
#include <kdl/frames.hpp>
60
#include <kdl/chainjnttojacsolver.hpp>
61
#include <
ros/node_handle.h
>
62
#include <geometry_msgs/Wrench.h>
63
#include <
pr2_controller_interface/controller.h
>
64
#include <
pr2_mechanism_model/chain.h
>
65
#include <
tf/transform_datatypes.h
>
66
#include <
realtime_tools/realtime_publisher.h
>
67
#include <boost/scoped_ptr.hpp>
68
#include <boost/thread/condition.hpp>
69
70
71
namespace
controller
{
72
73
class
CartesianWrenchController
:
public
pr2_controller_interface::Controller
74
{
75
public
:
76
CartesianWrenchController
();
77
~CartesianWrenchController
();
78
79
bool
init
(
pr2_mechanism_model::RobotState
*robot,
ros::NodeHandle
&n);
80
81
void
starting
();
82
void
update
();
83
84
// input of the controller
85
KDL::Wrench
wrench_desi_
;
86
87
private
:
88
ros::NodeHandle
node_
;
89
ros::Subscriber
sub_command_
;
90
void
command
(
const
geometry_msgs::WrenchConstPtr& wrench_msg);
91
pr2_mechanism_model::RobotState
*
robot_state_
;
92
pr2_mechanism_model::Chain
chain_
;
93
94
KDL::Chain
kdl_chain_
;
95
boost::scoped_ptr<KDL::ChainJntToJacSolver>
jnt_to_jac_solver_
;
96
KDL::JntArray
jnt_pos_
,
jnt_eff_
;
97
KDL::Jacobian
jacobian_
;
98
99
};
100
101
}
// namespace
102
103
104
#endif
controller::CartesianWrenchController::wrench_desi_
KDL::Wrench wrench_desi_
Definition:
cartesian_wrench_controller.h:85
ros::NodeHandle
controller::CartesianWrenchController::jnt_to_jac_solver_
boost::scoped_ptr< KDL::ChainJntToJacSolver > jnt_to_jac_solver_
Definition:
cartesian_wrench_controller.h:95
KDL::Jacobian
KDL::Chain
KDL::JntArray
controller::CartesianWrenchController::CartesianWrenchController
CartesianWrenchController()
Definition:
cartesian_wrench_controller.cpp:45
controller::CartesianWrenchController::jnt_pos_
KDL::JntArray jnt_pos_
Definition:
cartesian_wrench_controller.h:96
realtime_publisher.h
controller::CartesianWrenchController::init
bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
Definition:
cartesian_wrench_controller.cpp:58
controller::CartesianWrenchController
Definition:
cartesian_wrench_controller.h:73
transform_datatypes.h
controller::CartesianWrenchController::jacobian_
KDL::Jacobian jacobian_
Definition:
cartesian_wrench_controller.h:97
controller::CartesianWrenchController::sub_command_
ros::Subscriber sub_command_
Definition:
cartesian_wrench_controller.h:89
pr2_mechanism_model::Chain
controller::CartesianWrenchController::command
void command(const geometry_msgs::WrenchConstPtr &wrench_msg)
Definition:
cartesian_wrench_controller.cpp:139
ros::Subscriber
node_handle.h
controller::CartesianWrenchController::update
void update()
Definition:
cartesian_wrench_controller.cpp:113
pr2_mechanism_model::RobotState
controller.h
chain.h
controller::CartesianWrenchController::~CartesianWrenchController
~CartesianWrenchController()
Definition:
cartesian_wrench_controller.cpp:52
controller::CartesianWrenchController::chain_
pr2_mechanism_model::Chain chain_
Definition:
cartesian_wrench_controller.h:92
pr2_controller_interface::Controller
controller::CartesianWrenchController::jnt_eff_
KDL::JntArray jnt_eff_
Definition:
cartesian_wrench_controller.h:96
controller::CartesianWrenchController::robot_state_
pr2_mechanism_model::RobotState * robot_state_
Definition:
cartesian_wrench_controller.h:91
KDL::Wrench
controller
controller::CartesianWrenchController::starting
void starting()
Definition:
cartesian_wrench_controller.cpp:105
controller::CartesianWrenchController::kdl_chain_
KDL::Chain kdl_chain_
Definition:
cartesian_wrench_controller.h:94
controller::CartesianWrenchController::node_
ros::NodeHandle node_
Definition:
cartesian_wrench_controller.h:88
robot_mechanism_controllers
Author(s): John Hsu, Melonee Wise, Stuart Glaser
autogenerated on Mon Jun 10 2019 14:26:26