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

Fix build and demos #3

Closed
wants to merge 2 commits into from
Closed
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
2 changes: 1 addition & 1 deletion denso_robot_bringup/launch/denso_robot_bringup.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -376,7 +376,7 @@ def generate_launch_description():
# --------- Gazebo Nodes (only if 'sim:=true') ---------
set_param_use_sim_time = SetParameter(
name='use_sim_time', value=True,
condition=IfCondition(LaunchConfiguration('sim')))
condition=IfCondition(sim))

world_file = os.path.join(
get_package_share_directory('denso_robot_moveit_config'), 'worlds', 'empty.sdf')
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,20 +2,20 @@
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">

<xacro:macro name="denso_robot_ros2_control" params="name namespace
robot_name
robot_name
sim:=false fake_sensor_commands:=false
ip_address
model
robot_joints joint_1 joint_2 joint_3 joint_4 joint_5 joint_6
arm_group
send_format recv_format
controller_type
controller_type
verbose
">

<ros2_control name="${namespace}${name}" type="system">
<!-- joint limits include -->
<xacro:include filename="$(find denso_robot_descriptions)/robots/$(arg model)/urdf/denso_robot_joint_limits.xacro" />
<!-- joint limits include -->
<xacro:include filename="$(find denso_robot_descriptions)/robots/$(arg model)/urdf/denso_robot_joint_limits.xacro" />
<hardware>
<xacro:if value="${sim}">
<plugin>ign_ros2_control/IgnitionSystem</plugin>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -72,12 +72,12 @@
<xacro:denso_robot_arm_kinematics namespace="$(arg namespace)" model="$(arg model)" />

<gazebo>
<plugin filename="libign_ros2_control-system.so" name="ign_ros2_control::IgnitionROS2ControlPlugin" >
<plugin filename="libign_ros2_control-system.so" name="ign_ros2_control::IgnitionROS2ControlPlugin" >
<robot_param>robot_description</robot_param>
<robot_param_node>robot_state_publisher</robot_param_node>
<parameters>$(find denso_robot_moveit_config)/robots/$(arg model)/config/denso_robot_controllers.yaml</parameters>
</plugin>
</gazebo>
<parameters>$(find denso_robot_moveit_config)/robots/$(arg model)/config/denso_robot_controllers.yaml</parameters>
</plugin>
</gazebo>


</xacro:macro>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,23 +2,23 @@
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">

<xacro:macro name="denso_robot_ros2_control" params="name namespace
robot_name
robot_name
sim:=false fake_sensor_commands:=false
ip_address
model
robot_joints joint_1 joint_2 joint_3 joint_4
arm_group
send_format recv_format
controller_type
controller_type
verbose
">

<ros2_control name="${namespace}${name}" type="system">
<!-- joint limits include -->
<xacro:include filename="$(find denso_robot_descriptions)/robots/$(arg model)/urdf/denso_robot_joint_limits.xacro" />
<!-- joint limits include -->
<xacro:include filename="$(find denso_robot_descriptions)/robots/$(arg model)/urdf/denso_robot_joint_limits.xacro" />
<hardware>
<xacro:if value="${sim}">
<plugin>gazebo_ros2_control/GazeboSystem</plugin>
<plugin>ign_ros2_control/IgnitionSystem</plugin>
</xacro:if>
<xacro:unless value="${sim}">
<plugin>denso_robot_control/DensoRobotHW</plugin>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@
<xacro:include filename="$(find denso_robot_descriptions)/robots/$(arg model)/urdf/denso_robot.ros2_control.xacro" />
<!-- ros2 control instance -->
<xacro:denso_robot_ros2_control
name="GazeboSystem" namespace="$(arg namespace)"
name="IgnitionSystem" namespace="$(arg namespace)"
sim="$(arg sim)"
model="$(arg model)"
ip_address="$(arg ip_address)"
Expand All @@ -69,10 +69,12 @@
<xacro:denso_robot_arm_kinematics namespace="$(arg namespace)" model="$(arg model)" />

<gazebo>
<plugin filename="libgazebo_ros2_control.so" name="gazebo_ros2_control">
<parameters>$(find denso_robot_moveit_config)/robots/$(arg model)/config/denso_robot_controllers.yaml</parameters>
</plugin>
</gazebo>
<plugin filename="libign_ros2_control-system.so" name="ign_ros2_control::IgnitionROS2ControlPlugin" >
<robot_param>robot_description</robot_param>
<robot_param_node>robot_state_publisher</robot_param_node>
<parameters>$(find denso_robot_moveit_config)/robots/$(arg model)/config/denso_robot_controllers.yaml</parameters>
</plugin>
</gazebo>


</xacro:macro>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,23 +2,23 @@
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">

<xacro:macro name="denso_robot_ros2_control" params="name namespace
robot_name
robot_name
sim:=false fake_sensor_commands:=false
ip_address
model
robot_joints joint_1 joint_2 joint_3 joint_4 joint_5 joint_6
arm_group
send_format recv_format
controller_type
controller_type
verbose
">

<ros2_control name="${namespace}${name}" type="system">
<!-- joint limits include -->
<xacro:include filename="$(find denso_robot_descriptions)/robots/$(arg model)/urdf/denso_robot_joint_limits.xacro" />
<!-- joint limits include -->
<xacro:include filename="$(find denso_robot_descriptions)/robots/$(arg model)/urdf/denso_robot_joint_limits.xacro" />
<hardware>
<xacro:if value="${sim}">
<plugin>gazebo_ros2_control/GazeboSystem</plugin>
<plugin>ign_ros2_control/IgnitionSystem</plugin>
</xacro:if>
<xacro:unless value="${sim}">
<plugin>denso_robot_control/DensoRobotHW</plugin>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@
<xacro:include filename="$(find denso_robot_descriptions)/robots/$(arg model)/urdf/denso_robot.ros2_control.xacro" />
<!-- ros2 control instance -->
<xacro:denso_robot_ros2_control
name="GazeboSystem" namespace="$(arg namespace)"
name="IgnitionSystem" namespace="$(arg namespace)"
sim="$(arg sim)"
model="$(arg model)"
ip_address="$(arg ip_address)"
Expand All @@ -72,10 +72,12 @@
<xacro:denso_robot_arm_kinematics namespace="$(arg namespace)" model="$(arg model)" />

<gazebo>
<plugin filename="libgazebo_ros2_control.so" name="gazebo_ros2_control">
<parameters>$(find denso_robot_moveit_config)/robots/$(arg model)/config/denso_robot_controllers.yaml</parameters>
</plugin>
</gazebo>
<plugin filename="libign_ros2_control-system.so" name="ign_ros2_control::IgnitionROS2ControlPlugin" >
<robot_param>robot_description</robot_param>
<robot_param_node>robot_state_publisher</robot_param_node>
<parameters>$(find denso_robot_moveit_config)/robots/$(arg model)/config/denso_robot_controllers.yaml</parameters>
</plugin>
</gazebo>


</xacro:macro>
Expand Down
4 changes: 2 additions & 2 deletions denso_robot_drivers_ros2.repos
Original file line number Diff line number Diff line change
Expand Up @@ -2,8 +2,8 @@ repositories:
gazebo_ros2_control:
type: git
url: https://github.com/ros-simulation/gazebo_ros2_control.git
version: humble
version: humble
ros2_control_demos:
type: git
url: https://github.com/ros-controls/ros2_control_demos.git
version: master
version: humble
2 changes: 1 addition & 1 deletion denso_robot_moveit_demo/src/denso_robot_moveit_demo.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ class DensoRobotCppDemo
node_->create_publisher<moveit_msgs::msg::DisplayRobotState>("display_robot_state", 1))
{
node_->declare_parameter("model", "cobotta");
node_->declare_parameter("scale_factor", "1.0");
node_->declare_parameter("scale_factor", 1.0);
}

void run()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -56,8 +56,8 @@ class DensoRobotPickAndPlaceDemo
node_->create_publisher<moveit_msgs::msg::DisplayRobotState>("display_robot_state", 1))
{
node_->declare_parameter("model", "");
node_->declare_parameter("scale_factor", "");
node_->declare_parameter("num_cycles", "");
node_->declare_parameter("scale_factor", 1.0);
node_->declare_parameter("num_cycles", 1);
}

void run()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -55,8 +55,8 @@ class DensoRobotPickAndPlaceDemo
node_->create_publisher<moveit_msgs::msg::DisplayRobotState>("display_robot_state", 1))
{
node_->declare_parameter("model", "");
node_->declare_parameter("scale_factor", "");
node_->declare_parameter("num_cycles", "");
node_->declare_parameter("scale_factor", 1.0);
node_->declare_parameter("num_cycles", 1);
}

void run()
Expand Down