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

feat(franka_gazebo): add physics engine launch argument #211

Open
wants to merge 2 commits into
base: develop
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@ Requires `libfranka` >= 0.8.0
* `franka_description`: `<xacro:franka_robot/>` macro now supports to customize the `parent` frame and its `xyz` + `rpy` offset
* `franka_hw`: Fix the bug where the previous controller is still running after switching the controller. ([#326](https://github.com/frankaemika/franka_ros/issues/326))
* `franka_gazebo`: Add `set_franka_model_configuration` service.
* `franka_gazebo`: Add Gazebo simulation physics engine command line argument

## 0.10.1 - 2022-09-15

Expand Down
2 changes: 2 additions & 0 deletions franka_gazebo/launch/panda.launch
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
<arg name="paused" default="false" doc="Should the simulation directly be stopped at 0s?" />
<arg name="world" default="worlds/empty.world" doc="Filename to a SDF World for gazebo to use" />
<arg name="rviz" default="false" doc="Should RVIz be launched?" />
<arg name="physics" default="ode" doc="The physics engine used by gazebo"/> <!--Phyics engines: ode|dart-->

<!-- Robot Customization -->
<arg name="arm_id" default="panda" doc="Name of the robot to spawn" />
Expand Down Expand Up @@ -38,6 +39,7 @@
<arg name="paused" value="$(arg paused)" />
<arg name="world" value="$(arg world)" />
<arg name="rviz" value="$(arg rviz)" />
<arg name="physics" value="$(arg physics)" />

<arg name="robot" value="panda" />
<arg name="arm_id" value="$(arg arm_id)" />
Expand Down
2 changes: 2 additions & 0 deletions franka_gazebo/launch/robot.launch
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
<arg name="paused" default="false" doc="Should the simulation directly be stopped at 0s?" />
<arg name="world" default="worlds/empty.world" doc="Filename to a SDF World for gazebo to use" />
<arg name="rviz" default="false" doc="Should RVIz be launched?" />
<arg name="physics" default="ode" doc="The physics engine used by gazebo"/> <!--Phyics engines: ode|dart-->

<!-- Robot Customization -->
<arg name="robot" doc="Which robot to spawn (one of {panda,fr3})" />
Expand Down Expand Up @@ -40,6 +41,7 @@
<arg name="paused" value="true"/>
<arg name="gui" value="$(eval not arg('headless'))"/>
<arg name="use_sim_time" value="true"/>
<arg name="physics" value="$(arg physics)"/>
</include>

<param name="robot_description"
Expand Down
11 changes: 11 additions & 0 deletions franka_gazebo/src/franka_hw_sim.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -82,6 +82,17 @@ bool FrankaHWSim::initSim(const std::string& robot_namespace,

ROS_INFO_STREAM_NAMED("franka_hw_sim", "Using physics type " << physics->GetType());

// Print information about the used physics engine
std::vector<std::string> supported_engines{"ode", "dart"};
std::string physics_engine = physics->GetType();
ROS_INFO_STREAM_NAMED("franka_hw_sim", "Using physics type " << physics->GetType());
if (std::find(supported_engines.begin(), supported_engines.end(), physics_engine) ==
supported_engines.end()) {
ROS_ERROR_STREAM_NAMED("franka_hw_sim",
"The Panda Gazebo model does not yet officially support the '" +
physics_engine + "' physics engine.");
}

// Retrieve initial gravity vector from Gazebo
// NOTE: Can be overwritten by the user via the 'gravity_vector' ROS parameter.
auto gravity = physics->World()->Gravity();
Expand Down
Loading