include
velocity_limited_marker.h
Go to the documentation of this file.
1
/*
2
* Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
3
*
4
* Licensed under the Apache License, Version 2.0 (the "License");
5
* you may not use this file except in compliance with the License.
6
* You may obtain a copy of the License at
7
*
8
* http://www.apache.org/licenses/LICENSE-2.0
9
10
* Unless required by applicable law or agreed to in writing, software
11
* distributed under the License is distributed on an "AS IS" BASIS,
12
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13
* See the License for the specific language governing permissions and
14
* limitations under the License.
15
*/
16
17
18
#pragma once
19
#ifndef COB_VELOCITY_LIMITED_MARKER_H
20
#define COB_VELOCITY_LIMITED_MARKER_H
21
22
// ROS includes
23
#include <
ros/ros.h
>
24
25
// ROS message includes
26
#include <visualization_msgs/Marker.h>
27
28
namespace
cob_collision_velocity_filter
29
{
30
35
class
VelocityLimitedMarker
36
{
37
public
:
41
VelocityLimitedMarker
();
42
46
~VelocityLimitedMarker
();
47
51
void
createDirectionalMarkers
();
52
56
void
createRotationalMarkers
();
57
61
void
publishMarkers
(
double
vel_x_desired,
62
double
vel_x_actual,
63
double
vel_y_desired,
64
double
vel_y_actual,
65
double
vel_theta_desired,
66
double
vel_theta_actual);
67
72
void
interpolateColor
(
double
velocity, std_msgs::ColorRGBA& color);
73
74
protected
:
75
// Velocity limited markers
76
visualization_msgs::Marker
x_pos_marker_
,
x_neg_marker_
,
y_pos_marker_
,
y_neg_marker_
;
77
visualization_msgs::Marker
theta_pos_marker_
,
theta_neg_marker_
;
78
79
// a handle for this node
80
ros::NodeHandle
nh_
;
81
82
// Marker publisher
83
ros::Publisher
marker_pub_
;
84
85
// Is the marker disabled?
86
bool
disabled_
;
87
88
// Robot base frame
89
std::string
base_frame_
;
90
91
// Output topic name
92
std::string
topic_name_
;
93
94
// Marker lifetime
95
double
lifetime_
;
96
97
// Marker z-position
98
double
z_pos_
;
99
100
// last velocities
101
double
vx_last_
,
vy_last_
,
vtheta_last_
;
102
};
103
104
105
}
106
107
#endif // COB_VELOCITY_LIMITED_MARKER_H
108
cob_collision_velocity_filter::VelocityLimitedMarker::base_frame_
std::string base_frame_
Definition:
velocity_limited_marker.h:89
cob_collision_velocity_filter::VelocityLimitedMarker::z_pos_
double z_pos_
Definition:
velocity_limited_marker.h:98
ros::Publisher
cob_collision_velocity_filter::VelocityLimitedMarker::lifetime_
double lifetime_
Definition:
velocity_limited_marker.h:95
cob_collision_velocity_filter::VelocityLimitedMarker::theta_neg_marker_
visualization_msgs::Marker theta_neg_marker_
Definition:
velocity_limited_marker.h:77
cob_collision_velocity_filter::VelocityLimitedMarker::~VelocityLimitedMarker
~VelocityLimitedMarker()
Destructor.
Definition:
velocity_limited_marker.cpp:72
cob_collision_velocity_filter::VelocityLimitedMarker::x_pos_marker_
visualization_msgs::Marker x_pos_marker_
Definition:
velocity_limited_marker.h:76
cob_collision_velocity_filter::VelocityLimitedMarker::publishMarkers
void publishMarkers(double vel_x_desired, double vel_x_actual, double vel_y_desired, double vel_y_actual, double vel_theta_desired, double vel_theta_actual)
Creates all the markers, the method is called from the constructor.
Definition:
velocity_limited_marker.cpp:253
ros.h
cob_collision_velocity_filter::VelocityLimitedMarker::marker_pub_
ros::Publisher marker_pub_
Definition:
velocity_limited_marker.h:83
cob_collision_velocity_filter::VelocityLimitedMarker::topic_name_
std::string topic_name_
Definition:
velocity_limited_marker.h:92
cob_collision_velocity_filter::VelocityLimitedMarker::vtheta_last_
double vtheta_last_
Definition:
velocity_limited_marker.h:101
cob_collision_velocity_filter
Definition:
velocity_limited_marker.h:28
cob_collision_velocity_filter::VelocityLimitedMarker::interpolateColor
void interpolateColor(double velocity, std_msgs::ColorRGBA &color)
Calculates the color for the marker.
Definition:
velocity_limited_marker.cpp:235
cob_collision_velocity_filter::VelocityLimitedMarker::disabled_
bool disabled_
Definition:
velocity_limited_marker.h:86
cob_collision_velocity_filter::VelocityLimitedMarker::nh_
ros::NodeHandle nh_
Definition:
velocity_limited_marker.h:80
cob_collision_velocity_filter::VelocityLimitedMarker::createRotationalMarkers
void createRotationalMarkers()
Creates all rotational markers, the method is called from the constructor.
Definition:
velocity_limited_marker.cpp:159
cob_collision_velocity_filter::VelocityLimitedMarker
Definition:
velocity_limited_marker.h:35
cob_collision_velocity_filter::VelocityLimitedMarker::vx_last_
double vx_last_
Definition:
velocity_limited_marker.h:101
cob_collision_velocity_filter::VelocityLimitedMarker::y_neg_marker_
visualization_msgs::Marker y_neg_marker_
Definition:
velocity_limited_marker.h:76
cob_collision_velocity_filter::VelocityLimitedMarker::VelocityLimitedMarker
VelocityLimitedMarker()
Constructor.
Definition:
velocity_limited_marker.cpp:47
cob_collision_velocity_filter::VelocityLimitedMarker::createDirectionalMarkers
void createDirectionalMarkers()
Creates all directional markers, the method is called from the constructor.
Definition:
velocity_limited_marker.cpp:77
cob_collision_velocity_filter::VelocityLimitedMarker::y_pos_marker_
visualization_msgs::Marker y_pos_marker_
Definition:
velocity_limited_marker.h:76
cob_collision_velocity_filter::VelocityLimitedMarker::vy_last_
double vy_last_
Definition:
velocity_limited_marker.h:101
ros::NodeHandle
cob_collision_velocity_filter::VelocityLimitedMarker::theta_pos_marker_
visualization_msgs::Marker theta_pos_marker_
Definition:
velocity_limited_marker.h:77
cob_collision_velocity_filter::VelocityLimitedMarker::x_neg_marker_
visualization_msgs::Marker x_neg_marker_
Definition:
velocity_limited_marker.h:76
cob_collision_velocity_filter
Author(s): Matthias Gruhler, Michal Spanel
autogenerated on Wed May 1 2024 02:45:28