Skip to content
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
2 changes: 1 addition & 1 deletion canopen/sphinx/user-guide/cia402-driver.rst
Original file line number Diff line number Diff line change
Expand Up @@ -122,7 +122,7 @@ Additional parameters that can be used in bus.yml for this driver.
- Milliseconds
- Refresh period for 402 state machine. Should be similar to sync period of master.
* - switching_state
- see below
- ?
- The state to switch the operation mode in.
* - scale_pos_to_dev
- double
Expand Down
2 changes: 1 addition & 1 deletion canopen/sphinx/user-guide/configuration.rst
Original file line number Diff line number Diff line change
Expand Up @@ -88,7 +88,7 @@ but come from the lely core library. Below you find a list of possible configura
:widths: 1 1

configuration item; description
node_id; The node-ID (default: 255)
node_id; The node-ID (e.g. 255)
Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Not specifying it in bus.yml gives an error.

driver; The fully qualified class name of the master to use.
package; The ros2 package name in which the master class can be found.
namespace; The namespace in which the master will be created (default: "/").
Expand Down
39 changes: 5 additions & 34 deletions canopen/sphinx/user-guide/how-to-create-a-configuration.rst
Original file line number Diff line number Diff line change
Expand Up @@ -104,7 +104,7 @@ Bus configuration creation
.. code-block:: yaml

options:
dcf_path: install/{package_name}/share/{package_name}/config/{bus_config_name}
dcf_path: "@BUS_CONFIG_PATH@"
Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This is recommended I believe

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yes, this is correct.

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Well, depends if #403 gets merged first 🙂


Then you need to define your master.

Expand All @@ -126,7 +126,7 @@ Bus configuration creation
.. code-block:: yaml

nodes:
- [unique slave name]:
Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This should not be a list but a map.

[unique slave name]:
node_id: [node id]
package: [ros2 package where to find the driver]
driver: [qualified name of the driver]
Expand All @@ -141,8 +141,7 @@ Create a launch folder in your package directory and a launch file.

.. code-block:: console

mkdir launch
Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This directory was already created above.

touch {...}.launch.py
touch launch/{...}.launch.py
Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Added launch/ to indicate we're suddenly operating in different directories.


Add the following code:

Expand All @@ -169,12 +168,6 @@ Add the following code:
"{bus_config_name}",
"master.dcf",
),
"master_bin": os.path.join(
get_package_share_directory("{package_name}"),
"config",
"{bus_config_name}",
"master.bin",
),
"bus_config": os.path.join(
get_package_share_directory("{package_name}"),
"config",
Expand Down Expand Up @@ -206,36 +199,14 @@ Finally we need to adjust the CMakeLists.txt file to pick everything up correctl

# find dependencies
find_package(ament_cmake REQUIRED)
find_package(canopen_core REQUIRED)
find_package(canopen_interfaces REQUIRED)
find_package(canopen_base_driver REQUIRED)
find_package(canopen_proxy_driver REQUIRED)
Comment on lines -209 to -212
Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

These are unused

find_package(lely_core_libraries REQUIRED)


cogen_dcf({bus_config_name})

install(DIRECTORY
launch/
DESTINATION share/${PROJECT_NAME}/launch/
)

install(DIRECTORY
launch_tests/
Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This directory simply does not exist.

DESTINATION share/${PROJECT_NAME}/launch_tests/
launch
DESTINATION share/${PROJECT_NAME}
Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This is simply a cleanup. All other tutorials use this syntax, result is the same but this allows for more folders.

)


if(BUILD_TESTING)
Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think this is just noise on the tutorial.

find_package(ament_lint_auto REQUIRED)
# the following line skips the linter which checks for copyrights
# comment the line when a copyright and license is added to all source files
set(ament_cmake_copyright_FOUND TRUE)
# the following line skips cpplint (only works in a git repo)
# comment the line when this package is in a git repo and when
# a copyright and license is added to all source files
set(ament_cmake_cpplint_FOUND TRUE)
ament_lint_auto_find_test_dependencies()
endif()

ament_package()
2 changes: 1 addition & 1 deletion canopen/sphinx/user-guide/how-to-create-a-robot-system.rst
Original file line number Diff line number Diff line change
Expand Up @@ -223,4 +223,4 @@ leveragin ros2_control.

.. code-block:: bash

ros2 topic pub /joint1/forward_position_controller/command std_msgs/msg/Float64 "data: [1.0, 1.0]"
ros2 topic pub /joint_1/forward_position_controller/command std_msgs/msg/Float64 "data: [1.0, 1.0]"
Original file line number Diff line number Diff line change
Expand Up @@ -45,15 +45,15 @@ void NodeCanopenBaseDriver<rclcpp_lifecycle::LifecycleNode>::configure(bool call
}
RCLCPP_INFO_STREAM(
this->node_->get_logger(),
"Non transmit timeout" << static_cast<int>(this->non_transmit_timeout_.count()) << "ms");
"Non transmit timeout " << static_cast<int>(this->non_transmit_timeout_.count()) << "ms");

try
{
polling_ = this->config_["polling"].as<bool>();
}
catch (...)
{
RCLCPP_WARN(this->node_->get_logger(), "Could not polling from config, setting to true.");
RCLCPP_WARN(this->node_->get_logger(), "Could not read polling from config, setting to true.");
polling_ = true;
}
if (polling_)
Expand All @@ -78,7 +78,7 @@ void NodeCanopenBaseDriver<rclcpp_lifecycle::LifecycleNode>::configure(bool call
{
RCLCPP_WARN(
this->node_->get_logger(),
"Could not read enable diagnostics from config, setting to false.");
"Could not read `diagnostics/enable` from config, setting to false.");
diagnostic_enabled_ = false;
}
if (diagnostic_enabled_.load())
Expand All @@ -91,7 +91,7 @@ void NodeCanopenBaseDriver<rclcpp_lifecycle::LifecycleNode>::configure(bool call
{
RCLCPP_ERROR(
this->node_->get_logger(),
"Could not read diagnostics period from config, setting to 1000ms");
"Could not read `diagnostics/period` from config, setting to 1000ms");
diagnostic_period_ms_ = 1000;
}

Expand Down Expand Up @@ -132,15 +132,15 @@ void NodeCanopenBaseDriver<rclcpp::Node>::configure(bool called_from_base)
}
RCLCPP_INFO_STREAM(
this->node_->get_logger(),
"Non transmit timeout" << static_cast<int>(this->non_transmit_timeout_.count()) << "ms");
"Non transmit timeout " << static_cast<int>(this->non_transmit_timeout_.count()) << "ms");

try
{
polling_ = this->config_["polling"].as<bool>();
}
catch (...)
{
RCLCPP_WARN(this->node_->get_logger(), "Could not polling from config, setting to true.");
RCLCPP_WARN(this->node_->get_logger(), "Could not read polling from config, setting to true.");
polling_ = true;
}
if (polling_)
Expand All @@ -165,7 +165,7 @@ void NodeCanopenBaseDriver<rclcpp::Node>::configure(bool called_from_base)
{
RCLCPP_WARN(
this->node_->get_logger(),
"Could not read enable diagnostics from config, setting to false.");
"Could not read `diagnostics/enable` from config, setting to false.");
diagnostic_enabled_ = false;
}
if (diagnostic_enabled_.load())
Expand All @@ -178,7 +178,7 @@ void NodeCanopenBaseDriver<rclcpp::Node>::configure(bool called_from_base)
{
RCLCPP_WARN(
this->node_->get_logger(),
"Could not read diagnostics period from config, setting to 1000ms");
"Could not read `diagnostics/period` from config, setting to 1000ms");
diagnostic_period_ms_ = 1000;
}

Expand Down Expand Up @@ -294,7 +294,7 @@ void NodeCanopenBaseDriver<NODETYPE>::add_to_master()
bool boot_success = false;
int boot_attempts = 0;
const int max_boot_attempts = 3; // 1 retry allowed
RCLCPP_WARN(this->node_->get_logger(), "Wait for device to boot...");
RCLCPP_INFO(this->node_->get_logger(), "Wait for device to boot...");
while (!boot_success && boot_attempts < max_boot_attempts)
{
boot_attempts++;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ namespace node_interfaces
* @brief Node Canopen Master
*
* This class implements the NodeCanopenMasterInterface. It provides
* core functionality and logic for CanopenMaster, indepentently of the
* core functionality and logic for CanopenMaster, independently of the
* ROS node type. Currently rclcpp::Node and rclcpp_lifecycle::LifecycleNode
* and derived classes are supported. Other node types will lead to compile
* time error.
Expand Down Expand Up @@ -85,7 +85,7 @@ class NodeCanopenMaster : public NodeCanopenMasterInterface
std::string master_dcf_;
std::string master_bin_;
std::string can_interface_name_;
uint32_t timeout_;
uint32_t timeout_ = 2000;

std::thread spinner_;

Expand Down Expand Up @@ -169,18 +169,17 @@ class NodeCanopenMaster : public NodeCanopenMasterInterface

virtual void configure(bool called_from_base)
{
std::optional<int> timeout;
try
{
timeout = this->config_["boot_timeout"].as<int>();
this->timeout_ = this->config_["boot_timeout"].as<int>();
}
catch (...)
{
RCLCPP_WARN(
this->node_->get_logger(),
"No timeout parameter found in config file. Using default value of 100ms.");
"No `boot_timeout` parameter found in config file. Using default value of %dms.",
this->timeout_);
}
this->timeout_ = timeout.value_or(2000);
RCLCPP_INFO_STREAM(
this->node_->get_logger(), "Master boot timeout set to " << this->timeout_ << "ms.");
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -58,12 +58,12 @@ struct Cia402Data

if (!config["node_id"])
{
RCLCPP_ERROR(rclcpp::get_logger(joint_name), "No node id for '%s'", joint.name.c_str());
RCLCPP_INFO(rclcpp::get_logger(joint_name), "No node id for '%s'", joint.name.c_str());
return false;
}

node_id = config["node_id"].as<uint16_t>();
RCLCPP_ERROR(
RCLCPP_INFO(
rclcpp::get_logger(joint_name), "Node id for '%s' is '%u'", joint.name.c_str(), node_id);

if (config["position_mode"])
Expand Down