Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Remove deprecated old functions for ROS Melodic #91

Merged
merged 1 commit into from Aug 22, 2018
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
30 changes: 0 additions & 30 deletions include/rviz_visual_tools/rviz_visual_tools.h
Expand Up @@ -114,7 +114,6 @@ enum scales
XXLARGE = 9,
XXXLARGE = 10,
XXXXLARGE = 11,
REGULAR = 12 // deprecated as of ROS-KINETIC (remove in ROS-L)
};

enum EulerConvention
Expand Down Expand Up @@ -382,23 +381,8 @@ a * Warning: when using this in a loop be sure to call trigger() at end
* \brief Trigger the publish function to send out all collected markers
* \return true on success
*/
RVIZ_VISUAL_TOOLS_DEPRECATED
bool triggerBatchPublish()
{
return trigger();
}

bool trigger();

/**
* \brief Trigger the publish function to send out all collected markers. Also then turns off the
* batch mode. This is safer
* incase programmer forgets
* \return true on success
*/
RVIZ_VISUAL_TOOLS_DEPRECATED
bool triggerAndDisable();

/**
* \brief Display an array of markers, allows reuse of the ROS publisher
* \param markers
Expand Down Expand Up @@ -953,20 +937,6 @@ a * Warning: when using this in a loop be sure to call trigger() at end
*/
static geometry_msgs::Point convertPoint(const Eigen::Vector3d& point);

/**
* \brief Convert a 6-vector of x,y,z, roll,pitch,yall to an Affine3d with quaternion using Euler
* R-P-Y / X-Y-Z / 0-1-2 Euler Angle Standard
* \return 4x4 matrix in form of affine3d
* Use new function (below) instead, that specifies what type of convention. The drop in replacement
* for this function is:
* convertFromXYZRPY(x, y, z, roll, pitch, yaw, rviz_visual_tools::XYZ);
*/
RVIZ_VISUAL_TOOLS_DEPRECATED
static Eigen::Affine3d convertFromXYZRPY(double x, double y, double z, double roll, double pitch, double yaw);
RVIZ_VISUAL_TOOLS_DEPRECATED
static Eigen::Affine3d convertFromXYZRPY(const std::vector<double>& transform6); // TODO(davetcoleman): add new
// version of this function

/**
@brief Converts scalar translations and rotations to an Eigen Frame. This is achieved by chaining a
translation with individual euler rotations in ZYX order (this is equivalent to fixed rotatins XYZ)
Expand Down
29 changes: 0 additions & 29 deletions src/rviz_visual_tools.cpp
Expand Up @@ -655,12 +655,6 @@ std_msgs::ColorRGBA RvizVisualTools::getColorScale(double value) const

geometry_msgs::Vector3 RvizVisualTools::getScale(scales scale, double marker_scale) const
{
if (scale == REGULAR)
{
ROS_WARN_STREAM_ONCE_NAMED(name_, "Scale size 'REGULAR' is deprecated, please switch to 'MEDIUM'");
scale = MEDIUM;
}

geometry_msgs::Vector3 result;
double val(0.0);
switch (scale)
Expand Down Expand Up @@ -879,13 +873,6 @@ bool RvizVisualTools::trigger()
return result;
}

bool RvizVisualTools::triggerAndDisable()
{
trigger();
batch_publishing_enabled_ = false;
return true;
}

bool RvizVisualTools::publishMarkers(visualization_msgs::MarkerArray& markers)
{
if (pub_rviz_markers_ == nullptr)
Expand Down Expand Up @@ -2551,22 +2538,6 @@ geometry_msgs::Point RvizVisualTools::convertPoint(const Eigen::Vector3d& point)
return point_msg;
}

Eigen::Affine3d RvizVisualTools::convertFromXYZRPY(const std::vector<double>& transform6)
{
return convertFromXYZRPY(std::move(transform6), XYZ);
}

Eigen::Affine3d RvizVisualTools::convertFromXYZRPY(double x, double y, double z, double roll, double pitch, double yaw)
{
// R-P-Y / X-Y-Z / 0-1-2 Euler Angle Standard
Eigen::AngleAxisd roll_angle(roll, Eigen::Vector3d::UnitX());
Eigen::AngleAxisd pitch_angle(pitch, Eigen::Vector3d::UnitY());
Eigen::AngleAxisd yaw_angle(yaw, Eigen::Vector3d::UnitZ());
Eigen::Quaternion<double> quaternion = roll_angle * pitch_angle * yaw_angle;

return Eigen::Translation3d(x, y, z) * quaternion;
}

Eigen::Affine3d RvizVisualTools::convertFromXYZRPY(double tx, double ty, double tz, double rx, double ry, double rz,
EulerConvention convention)
{
Expand Down