Skip to content

Commit 6cb5df4

Browse files
committed
Merge branch 'noetic-devel' into tf2-migration
2 parents 808adee + da1b83c commit 6cb5df4

8 files changed

+35
-36
lines changed

src/rviz/default_plugin/depth_cloud_display.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -403,13 +403,13 @@ void DepthCloudDisplay::reset()
403403
setStatus( StatusProperty::Ok, "Message", "Ok" );
404404
}
405405

406-
void DepthCloudDisplay::processMessage(sensor_msgs::ImageConstPtr depth_msg)
406+
void DepthCloudDisplay::processMessage(const sensor_msgs::ImageConstPtr& depth_msg)
407407
{
408-
processMessage(std::move(depth_msg), sensor_msgs::ImageConstPtr());
408+
processMessage(depth_msg, sensor_msgs::ImageConstPtr());
409409
}
410410

411-
void DepthCloudDisplay::processMessage(sensor_msgs::ImageConstPtr depth_msg,
412-
sensor_msgs::ImageConstPtr rgb_msg)
411+
void DepthCloudDisplay::processMessage(const sensor_msgs::ImageConstPtr& depth_msg,
412+
const sensor_msgs::ImageConstPtr& rgb_msg)
413413
{
414414
if (context_->getFrameManager()->getPause() )
415415
{

src/rviz/default_plugin/depth_cloud_display.h

+3-2
Original file line numberDiff line numberDiff line change
@@ -152,8 +152,9 @@ protected Q_SLOTS:
152152

153153
typedef std::vector<rviz::PointCloud::Point> V_Point;
154154

155-
virtual void processMessage(sensor_msgs::Image::ConstPtr msg);
156-
virtual void processMessage(sensor_msgs::ImageConstPtr depth_msg, sensor_msgs::ImageConstPtr rgb_msg);
155+
virtual void processMessage(const sensor_msgs::Image::ConstPtr& msg);
156+
virtual void processMessage(const sensor_msgs::ImageConstPtr& depth_msg,
157+
const sensor_msgs::ImageConstPtr& rgb_msg);
157158
void caminfoCallback( sensor_msgs::CameraInfo::ConstPtr msg );
158159

159160
// overrides from Display

src/rviz/default_plugin/tf_display.cpp

+3-5
Original file line numberDiff line numberDiff line change
@@ -53,7 +53,7 @@ namespace rviz
5353
class FrameSelectionHandler: public SelectionHandler
5454
{
5555
public:
56-
FrameSelectionHandler( FrameInfo* frame, TFDisplay* display, DisplayContext* context );
56+
FrameSelectionHandler( FrameInfo* frame, DisplayContext* context );
5757
~FrameSelectionHandler() override {}
5858

5959
void createProperties( const Picked& obj, Property* parent_property ) override;
@@ -67,18 +67,16 @@ class FrameSelectionHandler: public SelectionHandler
6767

6868
private:
6969
FrameInfo* frame_;
70-
TFDisplay* display_;
7170
Property* category_property_;
7271
BoolProperty* enabled_property_;
7372
StringProperty* parent_property_;
7473
VectorProperty* position_property_;
7574
QuaternionProperty* orientation_property_;
7675
};
7776

78-
FrameSelectionHandler::FrameSelectionHandler(FrameInfo* frame, TFDisplay* display, DisplayContext* context )
77+
FrameSelectionHandler::FrameSelectionHandler(FrameInfo* frame, DisplayContext* context )
7978
: SelectionHandler( context )
8079
, frame_( frame )
81-
, display_( display )
8280
, category_property_( nullptr )
8381
, enabled_property_( nullptr )
8482
, parent_property_( nullptr )
@@ -416,7 +414,7 @@ FrameInfo* TFDisplay::createFrame(const std::string& frame)
416414
info->last_update_ = ros::Time::now();
417415
info->axes_ = new Axes( scene_manager_, axes_node_, 0.2, 0.02 );
418416
info->axes_->getSceneNode()->setVisible( show_axes_property_->getBool() );
419-
info->selection_handler_.reset( new FrameSelectionHandler( info, this, context_ ));
417+
info->selection_handler_.reset( new FrameSelectionHandler( info, context_ ));
420418
info->selection_handler_->addTrackedObjects( info->axes_->getSceneNode() );
421419

422420
info->name_text_ = new MovableText( frame, "Liberation Sans", 0.1 );

src/rviz/panel_dock_widget.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -141,7 +141,7 @@ void PanelDockWidget::save( Config config )
141141
config.mapSetValue( "collapsed", collapsed_ );
142142
}
143143

144-
void PanelDockWidget::load( Config config )
144+
void PanelDockWidget::load( const Config& config )
145145
{
146146
config.mapGetBool( "collapsed", &collapsed_ );
147147
}

src/rviz/panel_dock_widget.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -57,7 +57,7 @@ Q_OBJECT
5757
void setIcon( const QIcon& icon );
5858

5959
virtual void save( Config config );
60-
virtual void load( Config config );
60+
virtual void load( const Config& config );
6161

6262
/** @brief Override setVisible to respect the visibility override, */
6363
virtual void setVisible( bool visible );

src/test/config_sample.py

+3-4
Original file line numberDiff line numberDiff line change
@@ -2,13 +2,12 @@
22

33
import roslib; roslib.load_manifest('rviz')
44
import sys
5-
#setattr(sys, 'SELECT_QT_BINDING', 'pyside') # Shiboken
6-
setattr(sys, 'SELECT_QT_BINDING', 'pyqt') # SIP
7-
import python_qt_binding.QtBindingHelper # @UnusedImport
5+
setattr(sys, 'SELECT_QT_BINDING', 'pyqt')
6+
from python_qt_binding import QT_BINDING
87

98
from QtGui import *
109
from QtCore import *
11-
import rviz
10+
from rviz import bindings as rviz
1211

1312
c = rviz.Config()
1413
c.mapSetValue( "foo", 17 )

src/test/python_sample.py

+2-1
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,8 @@
1212
from python_qt_binding import QT_BINDING
1313
from python_qt_binding.QtGui import *
1414
from python_qt_binding.QtCore import *
15-
import rviz
15+
from python_qt_binding.QtWidgets import *
16+
from rviz import bindings as rviz
1617

1718
if QT_BINDING == 'pyside':
1819
print "Using PySide and shiboken for rviz python bindings."

src/test/send_covariance_msgs.py

+18-18
Original file line numberDiff line numberDiff line change
@@ -31,28 +31,27 @@
3131
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
3232
# POSSIBILITY OF SUCH DAMAGE.
3333

34-
import roslib; roslib.load_manifest( 'rviz_plugin_covariance' )
3534
from geometry_msgs.msg import PoseWithCovarianceStamped, PoseStamped
3635
import rospy
3736
from math import cos, sin, pi
38-
import tf
39-
import tf_conversions
37+
import tf2_ros
38+
import tf_conversions as tf
39+
from geometry_msgs.msg import TransformStamped, Vector3
4040

4141
publisher_cov = rospy.Publisher( 'pose_with_cov', PoseWithCovarianceStamped, queue_size=5 )
4242
publisher_pose = rospy.Publisher( 'pose', PoseStamped, queue_size=5 )
4343

4444
rospy.init_node( 'test_covariance' )
4545

46-
br = tf.TransformBroadcaster()
46+
br = tf2_ros.TransformBroadcaster()
4747
rate = rospy.Rate(100)
4848
# radius = 1
4949
angle = 0
5050
# r = 0
5151
# p = 0
5252
# y = 0
5353

54-
linear_deviation = 0.5;
55-
54+
linear_deviation = 0.5
5655

5756
while not rospy.is_shutdown():
5857
stamp = rospy.Time.now()
@@ -91,21 +90,22 @@
9190
publisher_cov.publish( pose_with_cov )
9291
publisher_pose.publish( pose )
9392

94-
# br.sendTransform((radius * cos(angle), radius * sin(angle), 0),
95-
# tf.transformations.quaternion_from_euler(r, p, y),
96-
# rospy.Time.now(),
97-
# "base_link",
98-
# "map")
99-
pos, ori = pose_with_cov.pose.pose.position, pose_with_cov.pose.pose.orientation
100-
br.sendTransform((pos.x, pos.y, pos.z),
101-
(ori.x, ori.y, ori.z, ori.w),
102-
stamp,
103-
"pose",
104-
"base_link")
93+
t = TransformStamped()
94+
t.header.frame_id = 'base_link'
95+
t.header.stamp = stamp
96+
t.child_frame_id = 'pose'
97+
98+
if 0:
99+
t.transform.translation = Vector3(radius * cos(angle), radius * sin(angle), 0)
100+
t.transform.rotation = tf.transformations.quaternion_from_euler(r, p, y)
101+
br.sendTransform(t)
102+
else:
103+
t.transform.translation = pose_with_cov.pose.pose.position
104+
t.transform.rotation = pose_with_cov.pose.pose.orientation
105+
br.sendTransform(t)
105106

106107
angle += .0005
107108
# r = angle
108109
# p = angle
109110
# y = angle
110111
rate.sleep()
111-

0 commit comments

Comments
 (0)