diff --git a/description/urdf/hexapod_robot_ros2_control.xacro b/description/urdf/hexapod_robot_ros2_control.xacro index 3cd608b..7b48214 100644 --- a/description/urdf/hexapod_robot_ros2_control.xacro +++ b/description/urdf/hexapod_robot_ros2_control.xacro @@ -27,13 +27,14 @@ - + ${i2c_address} ${channel} ${counts_intersect} ${counts_slope} ${counts_min} ${counts_max} + ${startup_value} @@ -41,29 +42,29 @@ hexapod_robot/HexapodRobotHardwareInterface /dev/i2c-1 - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + diff --git a/hardware/hexapod_robot_hwi.cpp b/hardware/hexapod_robot_hwi.cpp index ea1395f..fb82ab0 100644 --- a/hardware/hexapod_robot_hwi.cpp +++ b/hardware/hexapod_robot_hwi.cpp @@ -35,7 +35,6 @@ HexapodRobotHardwareInterface::on_init(const hardware_interface::HardwareInfo &i servos_powered_ = false; for (const hardware_interface::ComponentInfo &joint: info_.joints) { - joint_commands_[joint.name] = 0.0; std::string i2c_address_parameter = joint.name + "_i2c_address"; std::string channel_parameter = joint.name + "_channel"; @@ -43,6 +42,7 @@ HexapodRobotHardwareInterface::on_init(const hardware_interface::HardwareInfo &i std::string counts_slope_parameter = joint.name + "_counts_slope"; std::string counts_min_parameter = joint.name + "_counts_min"; std::string counts_max_parameter = joint.name + "_counts_max"; + std::string startup_value_parameter = joint.name + "_startup_value"; PWMOutput pwm_output; pwm_output.i2c_address = stoi(info_.hardware_parameters[i2c_address_parameter], nullptr, 0); @@ -51,6 +51,7 @@ HexapodRobotHardwareInterface::on_init(const hardware_interface::HardwareInfo &i pwm_output.counts_slope = stod(info_.hardware_parameters[counts_slope_parameter]); pwm_output.counts_min = stod(info_.hardware_parameters[counts_min_parameter]); pwm_output.counts_max = stod(info_.hardware_parameters[counts_max_parameter]); + joint_commands_[joint.name] = stod(info_.hardware_parameters[startup_value_parameter]); pca_available_[pwm_output.i2c_address] = false; joint_pwm_mapping_[joint.name] = pwm_output; @@ -60,7 +61,7 @@ HexapodRobotHardwareInterface::on_init(const hardware_interface::HardwareInfo &i i2c_available_ = i2c_open_(info_.hardware_parameters["i2c_device"]); - pca_initialize_(); + if(i2c_available_) pca_initialize_(); return hardware_interface::CallbackReturn::SUCCESS; }