Skip to content

Commit

Permalink
Merge branch 'main' into remove-humble-iron-repos-files
Browse files Browse the repository at this point in the history
  • Loading branch information
sea-bass authored Nov 16, 2024
2 parents 47f69d1 + f20265a commit 58b9e6e
Show file tree
Hide file tree
Showing 6 changed files with 13 additions and 10 deletions.
2 changes: 1 addition & 1 deletion .github/workflows/ci.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -167,7 +167,7 @@ jobs:
workdir: ${{ env.BASEDIR }}/target_ws
ignore: '"*/target_ws/build/*" "*/target_ws/install/*" "*/test/*"'
- name: Upload codecov report
uses: codecov/codecov-action@v4
uses: codecov/codecov-action@v5
if: always() && matrix.env.CCOV && steps.ici.outputs.target_test_results == '0'
with:
files: ${{ env.BASEDIR }}/target_ws/coverage.info
Expand Down
2 changes: 2 additions & 0 deletions moveit_core/robot_state/test/robot_state_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -781,6 +781,8 @@ TEST_F(OneRobot, rigidlyConnectedParent)
EXPECT_EQ(robot_model_->getRigidlyConnectedParentLinkModel(link_b), link_a);

moveit::core::RobotState state(robot_model_);
state.setToDefaultValues();
state.updateLinkTransforms();

EXPECT_EQ(state.getRigidlyConnectedParentLinkModel("link_b"), link_a);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -415,9 +415,10 @@ TEST_F(TrajectoryFunctionsTestFlangeAndGripper, testIKRobotStateWithIdentityColl
const moveit::core::LinkModel* tip_link = robot_model_->getLinkModel(tcp_link_);
Eigen::Isometry3d tip_pose_in_base = state.getFrameTransform(tcp_link_);

// Attach an object with no subframes, and no transform
// Attach an object with ignored subframes, and no transform
Eigen::Isometry3d object_pose_in_tip = Eigen::Isometry3d::Identity();
attachToLink(state, tip_link, "object", object_pose_in_tip, { {} });
moveit::core::FixedTransformsMap subframes({ { "ignored", Eigen::Isometry3d::Identity() } });
attachToLink(state, tip_link, "object", object_pose_in_tip, subframes);

// The RobotState should be able to use an object pose to set the joints
Eigen::Isometry3d object_pose_in_base = tip_pose_in_base * object_pose_in_tip;
Expand All @@ -440,12 +441,12 @@ TEST_F(TrajectoryFunctionsTestFlangeAndGripper, testIKRobotStateWithTransformedC
const moveit::core::LinkModel* tip_link = robot_model_->getLinkModel(tcp_link_);
Eigen::Isometry3d tip_pose_in_base = state.getFrameTransform(tcp_link_);

// Attach an object with no subframes, and a non-trivial transform
// Attach an object with ignored subframes, and a non-trivial transform
Eigen::Isometry3d object_pose_in_tip;
object_pose_in_tip = Eigen::Translation3d(1, 2, 3);
object_pose_in_tip *= Eigen::AngleAxis(M_PI_2, Eigen::Vector3d::UnitX());

attachToLink(state, tip_link, "object", object_pose_in_tip, { {} });
moveit::core::FixedTransformsMap subframes({ { "ignored", Eigen::Isometry3d::Identity() } });
attachToLink(state, tip_link, "object", object_pose_in_tip, subframes);

// The RobotState should be able to use an object pose to set the joints
Eigen::Isometry3d object_pose_in_base = tip_pose_in_base * object_pose_in_tip;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -356,10 +356,10 @@ void PlanningSceneDisplay::changedSceneName()
void PlanningSceneDisplay::renderPlanningScene()
{
QColor color = scene_color_property_->getColor();
Ogre::ColourValue env_color(color.redF(), color.greenF(), color.blueF());
Ogre::ColourValue env_color(color.redF(), color.greenF(), color.blueF(), scene_alpha_property_->getFloat());
if (attached_body_color_property_)
color = attached_body_color_property_->getColor();
Ogre::ColourValue attached_color(color.redF(), color.greenF(), color.blueF());
Ogre::ColourValue attached_color(color.redF(), color.greenF(), color.blueF(), robot_alpha_property_->getFloat());

try
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -91,7 +91,7 @@ void PlanningSceneRender::renderPlanningScene(const planning_scene::PlanningScen
color.r = default_attached_color.r;
color.g = default_attached_color.g;
color.b = default_attached_color.b;
color.a = 1.0f;
color.a = default_attached_color.a;
planning_scene::ObjectColorMap color_map;
scene->getKnownObjectColors(color_map);
scene_robot_->update(moveit::core::RobotStateConstPtr(rs), color, color_map);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -145,7 +145,7 @@ void RobotStateVisualization::updateHelper(const moveit::core::RobotStateConstPt
RCLCPP_ERROR_STREAM(getLogger(), "Link " << attached_body->getAttachedLinkName() << " not found in rviz::Robot");
continue;
}
Ogre::ColourValue rcolor(color.r, color.g, color.b);
Ogre::ColourValue rcolor(color.r, color.g, color.b, color.a);
const EigenSTL::vector_Isometry3d& ab_t = attached_body->getShapePosesInLinkFrame();
const std::vector<shapes::ShapeConstPtr>& ab_shapes = attached_body->getShapes();
for (std::size_t j = 0; j < ab_shapes.size(); ++j)
Expand Down

0 comments on commit 58b9e6e

Please sign in to comment.