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
6 changes: 3 additions & 3 deletions canopen_core/include/canopen_core/configuration_manager.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,8 +13,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef CONFIGURATION_MANAGER_HPP
#define CONFIGURATION_MANAGER_HPP
#ifndef CANOPEN_CORE__CONFIGURATION_MANAGER_HPP_
#define CANOPEN_CORE__CONFIGURATION_MANAGER_HPP_

#include <iostream>
#include <map>
Expand Down Expand Up @@ -108,4 +108,4 @@ class ConfigurationManager
};
} // namespace ros2_canopen

#endif
#endif // CANOPEN_CORE__CONFIGURATION_MANAGER_HPP_
12 changes: 6 additions & 6 deletions canopen_core/include/canopen_core/device_container.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,8 +13,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef LIFECYCLE_DEVICE_CONTAINER_NODE_HPP
#define LIFECYCLE_DEVICE_CONTAINER_NODE_HPP
#ifndef CANOPEN_CORE__DEVICE_CONTAINER_HPP_
#define CANOPEN_CORE__DEVICE_CONTAINER_HPP_

#include <chrono>
#include <memory>
Expand Down Expand Up @@ -149,11 +149,11 @@ class DeviceContainer : public rclcpp_components::ComponentManager
*/
virtual void shutdown()
{
for (auto it = registered_drivers_.begin(); it != registered_drivers_.end(); ++it)
for (auto & [_, interface] : registered_drivers_)
{
try
{
it->second->shutdown();
interface->shutdown();
}
catch (const std::exception & e)
{
Expand Down Expand Up @@ -267,7 +267,7 @@ class DeviceContainer : public rclcpp_components::ComponentManager
protected:
// Components
std::map<uint16_t, std::shared_ptr<CanopenDriverInterface>>
registered_drivers_; ///< Map of drivers registered in busconfiguration. Name is key.
registered_drivers_; ///< Map of drivers registered in busconfiguration. NodeID is key.
std::shared_ptr<ros2_canopen::CanopenMasterInterface>
can_master_; ///< Pointer to can master instance
uint16_t can_master_id_;
Expand Down Expand Up @@ -353,4 +353,4 @@ class DeviceContainer : public rclcpp_components::ComponentManager
};

} // namespace ros2_canopen
#endif // LIFECYCLE_DEVICE_CONTAINER_NODE_HPP
#endif // CANOPEN_CORE__DEVICE_CONTAINER_HPP_
6 changes: 3 additions & 3 deletions canopen_core/include/canopen_core/device_container_error.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef DEVICE_CONTAINER_ERROR_HPP_
#define DEVICE_CONTAINER_ERROR_HPP_
#ifndef CANOPEN_CORE__DEVICE_CONTAINER_ERROR_HPP_
#define CANOPEN_CORE__DEVICE_CONTAINER_ERROR_HPP_

#include <string>
#include <system_error>
Expand Down Expand Up @@ -41,4 +41,4 @@ class DeviceContainerException : public std::exception

} // namespace ros2_canopen

#endif
#endif // CANOPEN_CORE__DEVICE_CONTAINER_ERROR_HPP_
6 changes: 3 additions & 3 deletions canopen_core/include/canopen_core/driver_error.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef DRIVER_ERROR_HPP_
#define DRIVER_ERROR_HPP_
#ifndef CANOPEN_CORE__DRIVER_ERROR_HPP_
#define CANOPEN_CORE__DRIVER_ERROR_HPP_

#include <string>
#include <system_error>
Expand All @@ -40,4 +40,4 @@ class DriverException : public std::exception

} // namespace ros2_canopen

#endif
#endif // CANOPEN_CORE__DRIVER_ERROR_HPP_
6 changes: 3 additions & 3 deletions canopen_core/include/canopen_core/driver_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef DRIVER_NODE_HPP_
#define DRIVER_NODE_HPP_
#ifndef CANOPEN_CORE__DRIVER_NODE_HPP_
#define CANOPEN_CORE__DRIVER_NODE_HPP_

#include <rclcpp/rclcpp.hpp>
#include "canopen_core/node_interfaces/node_canopen_driver.hpp"
Expand Down Expand Up @@ -325,4 +325,4 @@ class LifecycleCanopenDriver : public CanopenDriverInterface, public rclcpp_life

} // namespace ros2_canopen

#endif
#endif // CANOPEN_CORE__DRIVER_NODE_HPP_
6 changes: 3 additions & 3 deletions canopen_core/include/canopen_core/exchange.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef EXCHANGE_HPP
#define EXCHANGE_HPP
#ifndef CANOPEN_CORE__EXCHANGE_HPP_
#define CANOPEN_CORE__EXCHANGE_HPP_

#include <boost/lockfree/queue.hpp>
#include <boost/optional.hpp>
Expand Down Expand Up @@ -151,4 +151,4 @@ class SafeQueue
};
} // namespace ros2_canopen

#endif // EXCHANGE_HPP
#endif // CANOPEN_CORE__EXCHANGE_HPP_
20 changes: 10 additions & 10 deletions canopen_core/include/canopen_core/lifecycle_manager.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef LIFECYCLE_DEVICE_MANAGER_NODE_HPP
#define LIFECYCLE_DEVICE_MANAGER_NODE_HPP
#ifndef CANOPEN_CORE__LIFECYCLE_MANAGER_HPP_
#define CANOPEN_CORE__LIFECYCLE_MANAGER_HPP_

#include <chrono>
#include <memory>
Expand Down Expand Up @@ -163,13 +163,13 @@ class LifecycleManager : public rclcpp_lifecycle::LifecycleNode
template <typename FutureT, typename WaitTimeT>
std::future_status wait_for_result(FutureT & future, WaitTimeT time_to_wait)
{
auto end = std::chrono::steady_clock::now() + time_to_wait;
std::chrono::milliseconds wait_period(100);
const auto end = std::chrono::steady_clock::now() + time_to_wait;
const std::chrono::milliseconds wait_period(100);
std::future_status status = std::future_status::timeout;
do
{
auto now = std::chrono::steady_clock::now();
auto time_left = end - now;
const auto now = std::chrono::steady_clock::now();
const auto time_left = end - now;
if (time_left <= std::chrono::seconds(0))
{
break;
Expand Down Expand Up @@ -248,8 +248,8 @@ class LifecycleManager : public rclcpp_lifecycle::LifecycleNode
/**
* @brief Brings up the drivers with specified node_id
*
* This function bringsup the CANopen driver for the device with the specified
* node_id. The driver is transitioned twice,
* This function brings up the CANopen driver for the device with the specified
* name. The driver is transitioned twice,
* first the configure transition is triggered. Once the transition is successfully
* finished, the activate transition is triggered.
*
Expand All @@ -263,7 +263,7 @@ class LifecycleManager : public rclcpp_lifecycle::LifecycleNode
* @brief Brings down the driver with specified node_id
*
* This function brings down the CANopen driver for the device with the specified
* node_id. The driver is transitioned twice,
* name. The driver is transitioned twice,
* first the deactivate transition is triggered. Once the transition is successfully
* finished, the cleanup transition is triggered.
*
Expand All @@ -286,4 +286,4 @@ class LifecycleManager : public rclcpp_lifecycle::LifecycleNode
};
} // namespace ros2_canopen

#endif
#endif // CANOPEN_CORE__LIFECYCLE_MANAGER_HPP_
6 changes: 3 additions & 3 deletions canopen_core/include/canopen_core/master_error.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef MASTER_ERROR_HPP_
#define MASTER_ERROR_HPP_
#ifndef CANOPEN_CORE__MASTER_ERROR_HPP_
#define CANOPEN_CORE__MASTER_ERROR_HPP_

#include <system_error>

Expand All @@ -38,4 +38,4 @@ class MasterException : public std::exception
};
} // namespace ros2_canopen

#endif
#endif // CANOPEN_CORE__MASTER_ERROR_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef NODE_CANOPEN_DRIVER_HPP_
#define NODE_CANOPEN_DRIVER_HPP_
#ifndef CANOPEN_CORE__NODE_CANOPEN_DRIVER_HPP_
#define CANOPEN_CORE__NODE_CANOPEN_DRIVER_HPP_

#include <yaml-cpp/yaml.h>
#include <atomic>
Expand Down Expand Up @@ -388,4 +388,4 @@ class NodeCanopenDriver : public NodeCanopenDriverInterface
} // namespace node_interfaces
} // namespace ros2_canopen

#endif
#endif // CANOPEN_CORE__NODE_CANOPEN_DRIVER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef NODE_CANOPEN_DRIVER_INTERFACE_HPP_
#define NODE_CANOPEN_DRIVER_INTERFACE_HPP_
#ifndef CANOPEN_CORE__NODE_CANOPEN_DRIVER_INTERFACE_HPP_
#define CANOPEN_CORE__NODE_CANOPEN_DRIVER_INTERFACE_HPP_

#include <lely/coapp/master.hpp>
#include <lely/ev/exec.hpp>
Expand Down Expand Up @@ -122,4 +122,4 @@ class NodeCanopenDriverInterface
} // namespace node_interfaces
} // namespace ros2_canopen

#endif
#endif // CANOPEN_CORE__NODE_CANOPEN_DRIVER_INTERFACE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef NODE_CANOPEN_MASTER_HPP_
#define NODE_CANOPEN_MASTER_HPP_
#ifndef CANOPEN_CORE__NODE_CANOPEN_MASTER_HPP_
#define CANOPEN_CORE__NODE_CANOPEN_MASTER_HPP_

#include <yaml-cpp/yaml.h>
#include <atomic>
Expand Down Expand Up @@ -389,4 +389,4 @@ class NodeCanopenMaster : public NodeCanopenMasterInterface
} // namespace node_interfaces
} // namespace ros2_canopen

#endif
#endif // CANOPEN_CORE__NODE_CANOPEN_MASTER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef NODE_CANOPEN_MASTER_INTERFACE_HPP_
#define NODE_CANOPEN_MASTER_INTERFACE_HPP_
#ifndef CANOPEN_CORE__NODE_CANOPEN_MASTER_INTERFACE_HPP_
#define CANOPEN_CORE__NODE_CANOPEN_MASTER_INTERFACE_HPP_

#include <lely/coapp/master.hpp>
#include <lely/ev/exec.hpp>
Expand Down Expand Up @@ -97,4 +97,5 @@ class NodeCanopenMasterInterface
};
} // namespace node_interfaces
} // namespace ros2_canopen
#endif

#endif // CANOPEN_CORE__NODE_CANOPEN_MASTER_INTERFACE_HPP_
22 changes: 11 additions & 11 deletions canopen_core/src/lifecycle_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,20 +70,20 @@ void LifecycleManager::init(std::shared_ptr<ros2_canopen::ConfigurationManager>

bool LifecycleManager::load_from_config()
{
std::vector<std::string> devices;
uint32_t count = this->config_->get_all_devices(devices);
std::vector<std::string> device_names;
uint32_t count = this->config_->get_all_devices(device_names);
RCLCPP_INFO(this->get_logger(), "Configuring for %u devices.", count);

// Find master in configuration
for (auto it = devices.begin(); it != devices.end(); it++)
for (const auto & device_name : device_names)
{
uint8_t node_id = config_->get_entry<uint8_t>(*it, "node_id").value();
std::string change_state_client_name = *it;
std::string get_state_client_name = *it;
uint8_t node_id = config_->get_entry<uint8_t>(device, "node_id").value();
std::string change_state_client_name = device_name;
std::string get_state_client_name = device_name;
get_state_client_name += "/get_state";
change_state_client_name += "/change_state";
RCLCPP_INFO(this->get_logger(), "Found %s (node_id=%hu)", it->c_str(), node_id);
device_names_to_ids.emplace(*it, node_id);
RCLCPP_INFO(this->get_logger(), "Found %s (node_id=%hu)", device_name.c_str(), node_id);
device_names_to_ids.emplace(device, node_id);
rclcpp::Client<lifecycle_msgs::srv::GetState>::SharedPtr get_state_client =
this->create_client<lifecycle_msgs::srv::GetState>(
get_state_client_name, rclcpp::QoS(10), cbg_clients);
Expand All @@ -95,7 +95,7 @@ bool LifecycleManager::load_from_config()
this->drivers_get_state_clients.emplace(node_id, get_state_client);
this->drivers_change_state_clients.emplace(node_id, change_state_client);

if (it->find("master") != std::string::npos)
if (device_name.find("master") != std::string::npos)
{
this->master_id_ = node_id;
}
Expand Down Expand Up @@ -212,9 +212,9 @@ bool LifecycleManager::bring_down_master()

bool LifecycleManager::bring_up_driver(std::string device_name)
{
auto node_id = this->device_names_to_ids[device_name];
const auto node_id = this->device_names_to_ids[device_name];
RCLCPP_DEBUG(this->get_logger(), "Bringing up %s with id %u", device_name.c_str(), node_id);
auto master_state = this->get_state(master_id_, 3s);
const auto master_state = this->get_state(master_id_, 3s);
if (master_state != lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
{
RCLCPP_ERROR(
Expand Down
Loading