Skip to content

Commit ba63491

Browse files
authored
indigo-devel backports from kinetic-devel (1.12.9) (#1110)
* Add fullscreen option. (#1017) * urdfdom compatibility (#1064) * Use urdf::*ShredPtr instead of boost::shared_ptr (#1044) urdfdom_headers uses C++ std::shared_ptr. As it exports it as custom *SharedPtr type, we can use the to sty compatible. This also adds a proper dependency for urdfdom-headers * adaptions to build against both urdfdom 0.3 and 0.4 ... relying on the compatibility layer of urdf package * Update display if empty pointcloud2 is published (#1073) Do not show last point cloud any more, if published point cloud message does not contain any points * Correctly scale the render panel on high resolution displays (#1078) * support multiple material for one link (#1079) * Fixed duplicate property name for Path colors (#1089) See issue #1087. * fix type error in newer versions of urdf (#1098) * Use unique material names for robot links. (#1102) * avoid C++11 feature for back port to indigo
1 parent 06b0485 commit ba63491

20 files changed

+186
-112
lines changed

CMakeLists.txt

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,8 @@ find_package(Boost REQUIRED
1717
thread
1818
)
1919

20+
find_package(urdfdom_headers REQUIRED)
21+
2022
find_package(PkgConfig REQUIRED)
2123

2224
find_package(ASSIMP QUIET)
@@ -129,6 +131,7 @@ find_package(catkin REQUIRED
129131
tf
130132
urdf
131133
visualization_msgs
134+
urdfdom_headers
132135
)
133136

134137
if(${tf_VERSION} VERSION_LESS "1.11.3")
@@ -210,6 +213,7 @@ include_directories(SYSTEM
210213
${OGRE_OV_INCLUDE_DIRS}
211214
${OPENGL_INCLUDE_DIR}
212215
${PYTHON_INCLUDE_PATH}
216+
${urdfdom_headers_INCLUDE_DIRS}
213217
)
214218
include_directories(src ${catkin_INCLUDE_DIRS})
215219

package.xml

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -49,6 +49,7 @@
4949
<build_depend>visualization_msgs</build_depend>
5050
<build_depend>yaml-cpp</build_depend>
5151
<build_depend>opengl</build_depend>
52+
<build_depend>liburdfdom-headers-dev</build_depend>
5253

5354
<run_depend>assimp</run_depend>
5455
<run_depend>eigen</run_depend>
@@ -81,6 +82,7 @@
8182
<run_depend>visualization_msgs</run_depend>
8283
<run_depend>yaml-cpp</run_depend>
8384
<run_depend>opengl</run_depend>
85+
<run_depend>liburdfdom-headers-dev</run_depend>
8486

8587
<export>
8688
<rviz plugin="${prefix}/plugin_description.xml"/>

src/rviz/default_plugin/effort_display.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -208,11 +208,11 @@ namespace rviz
208208
return;
209209
}
210210
setStatus(rviz::StatusProperty::Ok, "URDF", "Robot model parserd Ok");
211-
for (std::map<std::string, boost::shared_ptr<urdf::Joint> >::iterator it = robot_model_->joints_.begin(); it != robot_model_->joints_.end(); it ++ ) {
212-
boost::shared_ptr<urdf::Joint> joint = it->second;
211+
for (std::map<std::string, urdf::JointSharedPtr >::iterator it = robot_model_->joints_.begin(); it != robot_model_->joints_.end(); it ++ ) {
212+
urdf::JointSharedPtr joint = it->second;
213213
if ( joint->type == urdf::Joint::REVOLUTE ) {
214214
std::string joint_name = it->first;
215-
boost::shared_ptr<urdf::JointLimits> limit = joint->limits;
215+
urdf::JointLimitsSharedPtr limit = joint->limits;
216216
joints_[joint_name] = createJoint(joint_name);
217217
//joints_[joint_name]->max_effort_property_->setFloat(limit->effort);
218218
//joints_[joint_name]->max_effort_property_->setReadOnly( true );

src/rviz/default_plugin/effort_visual.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,7 @@ namespace rviz
3131

3232
// We create the arrow object within the frame node so that we can
3333
// set its position and direction relative to its header frame.
34-
for (std::map<std::string, boost::shared_ptr<urdf::Joint> >::iterator it = urdf_model_->joints_.begin(); it != urdf_model_->joints_.end(); it ++ ) {
34+
for (std::map<std::string, urdf::JointSharedPtr >::iterator it = urdf_model_->joints_.begin(); it != urdf_model_->joints_.end(); it ++ ) {
3535
if ( it->second->type == urdf::Joint::REVOLUTE ) {
3636
std::string joint_name = it->first;
3737
effort_enabled_[joint_name] = true;
@@ -103,7 +103,7 @@ namespace rviz
103103
if ( ! effort_enabled_[joint_name] ) continue;
104104

105105
//tf::Transform offset = poseFromJoint(joint);
106-
boost::shared_ptr<urdf::JointLimits> limit = joint->limits;
106+
urdf::JointLimitsSharedPtr limit = joint->limits;
107107
double max_effort = limit->effort, effort_value = 0.05;
108108

109109
if ( max_effort != 0.0 )

src/rviz/default_plugin/path_display.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -96,7 +96,7 @@ PathDisplay::PathDisplay()
9696
"Radius of the axes.",
9797
this, SLOT(updatePoseAxisGeometry()) );
9898

99-
pose_arrow_color_property_ = new ColorProperty( "Color",
99+
pose_arrow_color_property_ = new ColorProperty( "Pose Color",
100100
QColor( 255, 85, 255 ),
101101
"Color to draw the poses.",
102102
this, SLOT(updatePoseArrowColor()));

src/rviz/default_plugin/point_cloud2_display.cpp

Lines changed: 33 additions & 32 deletions
Original file line numberDiff line numberDiff line change
@@ -106,50 +106,51 @@ void PointCloud2Display::processMessage( const sensor_msgs::PointCloud2ConstPtr&
106106
}
107107

108108
filtered->data.resize(cloud->data.size());
109+
uint32_t output_count;
109110
if (point_count == 0)
110111
{
111-
return;
112-
}
113-
114-
uint8_t* output_ptr = &filtered->data.front();
115-
const uint8_t* ptr = &cloud->data.front(), *ptr_end = &cloud->data.back(), *ptr_init;
116-
size_t points_to_copy = 0;
117-
for (; ptr < ptr_end; ptr += point_step)
118-
{
119-
float x = *reinterpret_cast<const float*>(ptr + xoff);
120-
float y = *reinterpret_cast<const float*>(ptr + yoff);
121-
float z = *reinterpret_cast<const float*>(ptr + zoff);
122-
if (validateFloats(x) && validateFloats(y) && validateFloats(z))
112+
output_count = 0;
113+
} else {
114+
uint8_t* output_ptr = &filtered->data.front();
115+
const uint8_t* ptr = &cloud->data.front(), *ptr_end = &cloud->data.back(), *ptr_init;
116+
size_t points_to_copy = 0;
117+
for (; ptr < ptr_end; ptr += point_step)
123118
{
124-
if (points_to_copy == 0)
119+
float x = *reinterpret_cast<const float*>(ptr + xoff);
120+
float y = *reinterpret_cast<const float*>(ptr + yoff);
121+
float z = *reinterpret_cast<const float*>(ptr + zoff);
122+
if (validateFloats(x) && validateFloats(y) && validateFloats(z))
125123
{
126-
// Only memorize where to start copying from
127-
ptr_init = ptr;
128-
points_to_copy = 1;
124+
if (points_to_copy == 0)
125+
{
126+
// Only memorize where to start copying from
127+
ptr_init = ptr;
128+
points_to_copy = 1;
129+
}
130+
else
131+
{
132+
++points_to_copy;
133+
}
129134
}
130135
else
131136
{
132-
++points_to_copy;
137+
if (points_to_copy)
138+
{
139+
// Copy all the points that need to be copied
140+
memcpy(output_ptr, ptr_init, point_step*points_to_copy);
141+
output_ptr += point_step*points_to_copy;
142+
points_to_copy = 0;
143+
}
133144
}
134145
}
135-
else
146+
// Don't forget to flush what needs to be copied
147+
if (points_to_copy)
136148
{
137-
if (points_to_copy)
138-
{
139-
// Copy all the points that need to be copied
140-
memcpy(output_ptr, ptr_init, point_step*points_to_copy);
141-
output_ptr += point_step*points_to_copy;
142-
points_to_copy = 0;
143-
}
149+
memcpy(output_ptr, ptr_init, point_step*points_to_copy);
150+
output_ptr += point_step*points_to_copy;
144151
}
152+
output_count = (output_ptr - &filtered->data.front()) / point_step;
145153
}
146-
// Don't forget to flush what needs to be copied
147-
if (points_to_copy)
148-
{
149-
memcpy(output_ptr, ptr_init, point_step*points_to_copy);
150-
output_ptr += point_step*points_to_copy;
151-
}
152-
uint32_t output_count = (output_ptr - &filtered->data.front()) / point_step;
153154

154155
filtered->header = cloud->header;
155156
filtered->fields = cloud->fields;

src/rviz/ogre_helpers/render_system.cpp

Lines changed: 8 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -27,6 +27,8 @@
2727
* POSSIBILITY OF SUCH DAMAGE.
2828
*/
2929

30+
#include <sstream>
31+
3032
#include <QMetaType>
3133

3234
// This is required for QT_MAC_USE_COCOA to be set
@@ -342,7 +344,7 @@ int checkBadDrawable( Display* display, XErrorEvent* error )
342344
}
343345
#endif // Q_WS_X11
344346

345-
Ogre::RenderWindow* RenderSystem::makeRenderWindow( intptr_t window_id, unsigned int width, unsigned int height )
347+
Ogre::RenderWindow* RenderSystem::makeRenderWindow( intptr_t window_id, unsigned int width, unsigned int height, double pixel_ratio )
346348
{
347349
static int windowCounter = 0; // Every RenderWindow needs a unique name, oy.
348350

@@ -372,6 +374,11 @@ Ogre::RenderWindow* RenderSystem::makeRenderWindow( intptr_t window_id, unsigned
372374
#else
373375
params["macAPI"] = "carbon";
374376
#endif
377+
{
378+
std::stringstream ss;
379+
ss << pixel_ratio;
380+
params["contentScalingFactor"] = ss.str();
381+
}
375382

376383
std::ostringstream stream;
377384
stream << "OgreWindow(" << windowCounter++ << ")";

src/rviz/ogre_helpers/render_system.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -46,7 +46,7 @@ class RenderSystem
4646
public:
4747
static RenderSystem* get();
4848

49-
Ogre::RenderWindow* makeRenderWindow( intptr_t window_id, unsigned int width, unsigned int height );
49+
Ogre::RenderWindow* makeRenderWindow( intptr_t window_id, unsigned int width, unsigned int height, double pixel_ratio = 1.0 );
5050

5151
Ogre::Root* root() { return ogre_root_; }
5252

src/rviz/ogre_helpers/render_widget.cpp

Lines changed: 8 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -38,6 +38,9 @@
3838
#include <QPaintEvent>
3939
#include <QShowEvent>
4040
#include <QVBoxLayout>
41+
#if QT_VERSION >= QT_VERSION_CHECK(5, 0, 0)
42+
#include <QWindow>
43+
#endif
4144

4245
namespace rviz
4346
{
@@ -83,8 +86,12 @@ RenderWidget::RenderWidget( RenderSystem* render_system, QWidget *parent )
8386

8487
#if QT_VERSION < QT_VERSION_CHECK(5, 0, 0)
8588
QApplication::syncX();
89+
double pixel_ratio = 1.0;
90+
#else
91+
QWindow* window = windowHandle();
92+
double pixel_ratio = window ? window->devicePixelRatio() : 1.0;
8693
#endif
87-
render_window_ = render_system_->makeRenderWindow( win_id, width(), height() );
94+
render_window_ = render_system_->makeRenderWindow( win_id, width(), height(), pixel_ratio );
8895
}
8996

9097
RenderWidget::~RenderWidget()

src/rviz/panel_dock_widget.cpp

Lines changed: 14 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -100,13 +100,13 @@ void PanelDockWidget::setCollapsed( bool collapse )
100100
{
101101
if ( isVisible() )
102102
{
103-
QDockWidget::setVisible( false );
103+
PanelDockWidget::setVisible( false );
104104
collapsed_ = collapse;
105105
}
106106
}
107107
else
108108
{
109-
QDockWidget::setVisible( true );
109+
PanelDockWidget::setVisible( true );
110110
collapsed_ = collapse;
111111
}
112112
}
@@ -144,4 +144,16 @@ void PanelDockWidget::load( Config config )
144144
config.mapGetBool( "collapsed", &collapsed_ );
145145
}
146146

147+
void PanelDockWidget::setVisible( bool visible )
148+
{
149+
requested_visibility_ = visible;
150+
QDockWidget::setVisible(requested_visibility_ && !forced_hidden_);
151+
}
152+
153+
void PanelDockWidget::overrideVisibility( bool hidden )
154+
{
155+
forced_hidden_ = hidden;
156+
setVisible(requested_visibility_);
157+
}
158+
147159
} // end namespace rviz

0 commit comments

Comments
 (0)