include
ethercat_trigger_controllers
projector_controller.h
Go to the documentation of this file.
1
2
/*********************************************************************
3
* Software License Agreement (BSD License)
4
*
5
* Copyright (c) 2009, Willow Garage, Inc.
6
* All rights reserved.
7
*
8
* Redistribution and use in source and binary forms, with or without
9
* modification, are permitted provided that the following conditions
10
* are met:
11
*
12
* * Redistributions of source code must retain the above copyright
13
* notice, this list of conditions and the following disclaimer.
14
* * Redistributions in binary form must reproduce the above
15
* copyright notice, this list of conditions and the following
16
* disclaimer in the documentation and/or other materials provided
17
* with the distribution.
18
* * Neither the name of the Willow Garage nor the names of its
19
* contributors may be used to endorse or promote products derived
20
* from this software without specific prior written permission.
21
*
22
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33
* POSSIBILITY OF SUCH DAMAGE.
34
*********************************************************************/
35
#ifndef PROJECTOR_CONTROLLER_H
36
#define PROJECTOR_CONTROLLER_H
37
38
#include <
ros/node_handle.h
>
39
#include <
pr2_controller_interface/controller.h
>
40
#include <
pr2_mechanism_model/robot.h
>
41
#include <
realtime_tools/realtime_publisher.h
>
42
#include <std_msgs/Header.h>
43
#include <boost/scoped_ptr.hpp>
44
45
namespace
controller
46
{
47
class
ProjectorController :
public
pr2_controller_interface::Controller
48
{
49
public
:
50
ProjectorController
();
51
52
~ProjectorController
();
53
54
void
update
();
55
void
starting
();
56
void
stopping
();
57
58
bool
init
(
pr2_mechanism_model::RobotState
*robot,
ros::NodeHandle
&n);
59
60
private
:
61
pr2_mechanism_model::RobotState
*
robot_
;
62
pr2_hardware_interface::Projector
*
projector_
;
63
64
uint32_t
old_rising_
;
65
uint32_t
old_falling_
;
66
67
boost::scoped_ptr<
68
realtime_tools::RealtimePublisher
<
69
std_msgs::Header> >
rising_edge_pub_
,
falling_edge_pub_
;
70
71
ros::NodeHandle
node_handle_
;
72
73
// Configuration of controller.
74
std::string
actuator_name_
;
75
76
double
current_setting_
;
77
78
double
start_time_
;
79
};
80
81
};
82
83
#endif
84
realtime_publisher.h
node_handle.h
controller::ProjectorController::starting
void starting()
Definition:
projector_controller.cpp:88
controller::ProjectorController::init
bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
Definition:
projector_controller.cpp:106
controller::ProjectorController::current_setting_
double current_setting_
Definition:
projector_controller.h:140
controller::ProjectorController::node_handle_
ros::NodeHandle node_handle_
Definition:
projector_controller.h:135
realtime_tools::RealtimePublisher
controller.h
controller
controller::ProjectorController::rising_edge_pub_
boost::scoped_ptr< realtime_tools::RealtimePublisher< std_msgs::Header > > rising_edge_pub_
Definition:
projector_controller.h:133
pr2_mechanism_model::RobotState
controller::ProjectorController::actuator_name_
std::string actuator_name_
Definition:
projector_controller.h:138
controller::ProjectorController::stopping
void stopping()
Definition:
projector_controller.cpp:98
pr2_controller_interface::Controller
controller::ProjectorController::old_rising_
uint32_t old_rising_
Definition:
projector_controller.h:128
controller::ProjectorController::falling_edge_pub_
boost::scoped_ptr< realtime_tools::RealtimePublisher< std_msgs::Header > > falling_edge_pub_
Definition:
projector_controller.h:133
controller::ProjectorController::ProjectorController
ProjectorController()
Definition:
projector_controller.cpp:44
controller::ProjectorController::~ProjectorController
~ProjectorController()
Definition:
projector_controller.cpp:49
controller::ProjectorController::projector_
pr2_hardware_interface::Projector * projector_
Definition:
projector_controller.h:126
controller::ProjectorController::start_time_
double start_time_
Definition:
projector_controller.h:142
pr2_hardware_interface::Projector
controller::ProjectorController::robot_
pr2_mechanism_model::RobotState * robot_
Definition:
projector_controller.h:125
controller::ProjectorController::update
void update()
Definition:
projector_controller.cpp:53
ros::NodeHandle
robot.h
controller::ProjectorController::old_falling_
uint32_t old_falling_
Definition:
projector_controller.h:129
ethercat_trigger_controllers
Author(s): Blaise Gassend
autogenerated on Sat Nov 12 2022 03:33:17