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

Initialize MotionData using initial values from ros2_control xacro #45

Open
wants to merge 3 commits into
base: rolling
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
24 changes: 23 additions & 1 deletion abb_hardware_interface/src/abb_hardware_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,7 @@ CallbackReturn ABBSystemHardware::on_init(const hardware_interface::HardwareInfo
RCLCPP_INFO_STREAM(LOGGER, "Robot controller description:\n"
<< abb::robot::summaryText(robot_controller_description_));

std::vector<abb::robot::InitialJointValue> initial_joint_values = {};
for (const hardware_interface::ComponentInfo& joint : info_.joints)
{
if (joint.command_interfaces.size() != 2)
Expand Down Expand Up @@ -89,6 +90,27 @@ CallbackReturn ABBSystemHardware::on_init(const hardware_interface::HardwareInfo
joint.name.c_str(), joint.state_interfaces[1].name.c_str(), hardware_interface::HW_IF_VELOCITY);
return CallbackReturn::ERROR;
}
// Set the initial values for state and position interfaces.
auto get_value_from_info =
[](const std::string& info_value) -> double
{
if (info_value.empty())
return 0.0;
try
{
return std::stod(info_value);
}
catch(const std::exception& e)
{
return 0.0;
}
};
abb::robot::InitialJointValue initial_value;
initial_value.position_state = get_value_from_info(joint.state_interfaces[0].initial_value);
initial_value.velocity_state = get_value_from_info(joint.state_interfaces[1].initial_value);
initial_value.position_command = get_value_from_info(joint.command_interfaces[0].initial_value);
initial_value.velocity_command = get_value_from_info(joint.command_interfaces[1].initial_value);
initial_joint_values.push_back(std::move(initial_value));
}

// Configure EGM
Expand All @@ -97,7 +119,7 @@ CallbackReturn ABBSystemHardware::on_init(const hardware_interface::HardwareInfo
// Initialize motion data from robot controller description
try
{
abb::robot::initializeMotionData(motion_data_, robot_controller_description_);
abb::robot::initializeMotionData(motion_data_, robot_controller_description_, initial_joint_values);
}
catch (...)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,23 +26,33 @@
<command_interface name="position">
<param name="min">{-2*pi}</param>
<param name="max">{2*pi}</param>
<param name="initial_value">0.0</param>
</command_interface>
<command_interface name="velocity">
<param name="initial_value">0.0</param>
</command_interface>
<command_interface name="velocity"/>
<state_interface name="position">
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="velocity">
<param name="initial_value">0.0</param>
</state_interface>
</joint>
<joint name="${prefix}joint_2">
<command_interface name="position">
<param name="min">-2.41</param>
<param name="max">2.41</param>
<param name="initial_value">0.0</param>
</command_interface>
<command_interface name="velocity">
<param name="initial_value">0.0</param>
</command_interface>
<command_interface name="velocity"/>
<state_interface name="position">
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="velocity">
<param name="initial_value">0.0</param>
</state_interface>
</joint>
<joint name="${prefix}joint_3">
<command_interface name="position">
Expand All @@ -59,34 +69,49 @@
<command_interface name="position">
<param name="min">-2.66</param>
<param name="max">2.66</param>
<param name="initial_value">0.0</param>
</command_interface>
<command_interface name="velocity">
<param name="initial_value">0.0</param>
</command_interface>
<command_interface name="velocity"/>
<state_interface name="position">
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="velocity">
<param name="initial_value">0.0</param>
</state_interface>
</joint>
<joint name="${prefix}joint_5">
<command_interface name="position">
<param name="min">{-2*pi}</param>
<param name="max">{2*pi}</param>
<param name="initial_value">0.0</param>
</command_interface>
<command_interface name="velocity">
<param name="initial_value">0.0</param>
</command_interface>
<command_interface name="velocity"/>
<state_interface name="position">
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="velocity">
<param name="initial_value">0.0</param>
</state_interface>
</joint>
<joint name="${prefix}joint_6">
<command_interface name="position">
<param name="min">-2.23</param>
<param name="max">2.23</param>
<param name="initial_value">0.0</param>
</command_interface>
<command_interface name="velocity">
<param name="initial_value">0.0</param>
</command_interface>
<command_interface name="velocity"/>
<state_interface name="position">
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="velocity">
<param name="initial_value">0.0</param>
</state_interface>
</joint>
</ros2_control>
</xacro:macro>
Expand Down