19 #include "../../include/robotis_manipulator/robotis_manipulator.h" 47 Eigen::Vector3d world_position,
48 Eigen::Matrix3d world_orientation)
56 Eigen::Vector3d relative_position,
57 Eigen::Matrix3d relative_orientation,
58 Eigen::Vector3d axis_of_rotation,
59 int8_t joint_actuator_id,
60 double max_position_limit,
61 double min_position_limit,
64 Eigen::Matrix3d inertia_tensor,
65 Eigen::Vector3d center_of_mass,
66 double torque_coefficient)
69 relative_position, relative_orientation, axis_of_rotation, joint_actuator_id,
70 max_position_limit, min_position_limit, coefficient, mass,
71 inertia_tensor, center_of_mass, torque_coefficient);
81 Eigen::Vector3d relative_position,
82 Eigen::Matrix3d relative_orientation,
84 double max_position_limit,
85 double min_position_limit,
88 Eigen::Matrix3d object_inertia_tensor,
89 Eigen::Vector3d object_center_of_mass)
92 relative_position, relative_orientation, tool_id,
93 max_position_limit, min_position_limit, coefficient, object_mass,
94 object_inertia_tensor, object_center_of_mass);
125 for(uint32_t index = 0; index < id_array.size(); index++)
134 tool_actuator_.insert(std::make_pair(actuator_name, tool_actuator));
231 log::warn(
"[jacobian] Kinematics Class was not added.");
242 log::warn(
"[solveForwardKinematics] Kinematics Class was not added.");
255 log::warn(
"[solveForwardKinematics] Kinematics Class was not added.");
265 log::warn(
"[solveInverseKinematics] Kinematics Class was not added.");
276 log::warn(
"[setKinematicsOption] Kinematics Class was not added.");
295 log::warn(
"[solveForwardDynamics] Dynamics Class was not added.");
305 log::warn(
"[solveInverseDynamics] Dynamics Class was not added.");
321 log::warn(
"[solveInverseDynamics] Dynamics Class was not added.");
332 log::warn(
"[setDynamicsOption] Dynamics Class was not added.");
342 log::warn(
"[setDynamicsEnvironments] Dynamics Class was not added.");
464 std::map<Name, JointActuator *>::iterator it_joint_actuator;
477 std::map<Name, JointActuator *>::iterator it_joint_actuator;
489 std::map<Name, ToolActuator *>::iterator it_tool_actuator;
502 std::map<Name, ToolActuator *>::iterator it_tool_actuator;
514 std::map<Name, JointActuator *>::iterator it_joint_actuator;
519 std::map<Name, ToolActuator *>::iterator it_tool_actuator;
532 std::map<Name, JointActuator *>::iterator it_joint_actuator;
537 std::map<Name, ToolActuator *>::iterator it_tool_actuator;
576 std::vector<uint8_t> id;
577 std::vector<JointValue> value_vector;
579 value_vector.push_back(value);
593 if(joint_component_name.size() != value_vector.size())
598 std::vector<int8_t> joint_id;
599 for(uint32_t index = 0; index < value_vector.size(); index++)
603 value_vector.at(index).position = value_vector.at(index).position / coefficient;
604 value_vector.at(index).velocity = value_vector.at(index).velocity / coefficient;
605 value_vector.at(index).acceleration = value_vector.at(index).acceleration / coefficient;
606 value_vector.at(index).effort = value_vector.at(index).effort / torque_coefficient;
610 std::vector<uint8_t> single_actuator_id;
611 std::vector<JointValue> single_value_vector;
612 std::map<Name, JointActuator *>::iterator it_joint_actuator;
615 single_actuator_id =
joint_actuator_.at(it_joint_actuator->first)->getId();
616 for(uint32_t index = 0; index < single_actuator_id.size(); index++)
618 for(uint32_t index2=0; index2 < joint_id.size(); index2++)
620 if(single_actuator_id.at(index) == joint_id.at(index2))
622 single_value_vector.push_back(value_vector.at(index2));
626 joint_actuator_.at(it_joint_actuator->first)->sendJointActuatorValue(single_actuator_id, single_value_vector);
633 for(uint8_t index = 0; index < joint_component_name.size(); index++)
643 std::map<Name, Component>::iterator it;
644 std::vector<int8_t> joint_id;
652 value_vector.at(index).position = value_vector.at(index).position / coefficient;
653 value_vector.at(index).velocity = value_vector.at(index).velocity / coefficient;
654 value_vector.at(index).acceleration = value_vector.at(index).acceleration / coefficient;
655 value_vector.at(index).effort = value_vector.at(index).effort / torque_coefficient;
661 std::vector<uint8_t> single_actuator_id;
662 std::vector<JointValue> single_value_vector;
663 std::map<Name, JointActuator *>::iterator it_joint_actuator;
666 single_actuator_id =
joint_actuator_.at(it_joint_actuator->first)->getId();
667 for(uint32_t index = 0; index < single_actuator_id.size(); index++)
669 for(uint32_t index2=0; index2 < joint_id.size(); index2++)
671 if(single_actuator_id.at(index) == joint_id.at(index2))
673 single_value_vector.push_back(value_vector.at(index2));
677 joint_actuator_.at(it_joint_actuator->first)->sendJointActuatorValue(single_actuator_id, single_value_vector);
693 std::vector<uint8_t> actuator_id;
694 std::vector<JointValue> result;
696 actuator_id.push_back(static_cast<uint8_t>(
manipulator_.
getId(joint_component_name)));
702 result.at(0).position = result.at(0).position * coefficient;
703 result.at(0).velocity = result.at(0).velocity * coefficient;
704 result.at(0).acceleration = result.at(0).acceleration * coefficient;
705 result.at(0).effort = result.at(0).effort * torque_coefficient;
717 std::vector<JointValue> get_value_vector;
718 std::vector<uint8_t> get_actuator_id;
720 std::vector<JointValue> single_value_vector;
721 std::vector<uint8_t> single_actuator_id;
722 std::map<Name, JointActuator *>::iterator it_joint_actuator;
725 single_actuator_id =
joint_actuator_.at(it_joint_actuator->first)->getId();
726 single_value_vector =
joint_actuator_.at(it_joint_actuator->first)->receiveJointActuatorValue(single_actuator_id);
727 for(uint32_t index=0; index < single_actuator_id.size(); index++)
729 get_actuator_id.push_back(single_actuator_id.at(index));
730 get_value_vector.push_back(single_value_vector.at(index));
734 std::vector<JointValue> result_vector;
737 for(uint32_t index = 0; index < joint_component_name.size(); index++)
739 for(uint32_t index2 = 0; index2 < get_actuator_id.size(); index2++)
741 if(
manipulator_.
getId(joint_component_name.at(index)) == get_actuator_id.at(index2))
745 result.
position = get_value_vector.at(index2).position * coefficient;
746 result.
velocity = get_value_vector.at(index2).velocity * coefficient;
747 result.
acceleration = get_value_vector.at(index2).acceleration * coefficient;
748 result.
effort = get_value_vector.at(index2).effort * torque_coefficient;
750 result_vector.push_back(result);
755 return result_vector;
764 std::vector<JointValue> get_value_vector;
765 std::vector<uint8_t> get_actuator_id;
766 std::vector<JointValue> single_value_vector;
767 std::vector<uint8_t> single_actuator_id;
770 single_actuator_id =
joint_actuator_.at(it_joint_actuator->first)->getId();
771 single_value_vector =
joint_actuator_.at(it_joint_actuator->first)->receiveJointActuatorValue(single_actuator_id);
773 for(uint32_t index=0; index < single_actuator_id.size(); index++)
775 get_actuator_id.push_back(single_actuator_id.at(index));
776 get_value_vector.push_back(single_value_vector.at(index));
780 std::map<Name, Component>::iterator it;
781 std::vector<JointValue> result_vector;
785 for(uint32_t index2 = 0; index2 < get_actuator_id.size(); index2++)
791 result.
position = get_value_vector.at(index2).position * coefficient;
792 result.
velocity = get_value_vector.at(index2).velocity * coefficient;
793 result.
acceleration = get_value_vector.at(index2).acceleration * coefficient;
794 result.
effort = get_value_vector.at(index2).effort * torque_coefficient;
796 result_vector.push_back(result);
801 return result_vector;
833 for (uint32_t index = 0; index < tool_component_name.size(); index++)
836 value_vector.at(index).position = value_vector.at(index).position / coefficient;
837 value_vector.at(index).velocity = value_vector.at(index).velocity / coefficient;
838 value_vector.at(index).acceleration = value_vector.at(index).acceleration / coefficient;
848 for(uint8_t index = 0; index < tool_component_name.size(); index++)
858 std::vector<Name> tool_component_name;
860 for (uint32_t index = 0; index < tool_component_name.size(); index++)
863 value_vector.at(index).position = value_vector.at(index).position / coefficient;
864 value_vector.at(index).velocity = value_vector.at(index).velocity / coefficient;
865 value_vector.at(index).acceleration = value_vector.at(index).acceleration / coefficient;
902 std::vector<JointValue> result_vector;
904 for (uint32_t index = 0; index < tool_component_name.size(); index++)
914 result_vector.push_back(result);
916 return result_vector;
925 std::vector<Name> tool_component_name;
927 std::vector<JointValue> result_vector;
929 for (uint32_t index = 0; index < tool_component_name.size(); index++)
938 result_vector.push_back(result);
940 return result_vector;
987 log::error(
"[checkJointLimit] Goal value exceeded limit at " +
STRING(component_name) +
".");
998 log::error(
"[checkJointLimit] Goal value exceeded limit at " +
STRING(component_name) +
".");
1005 for(uint32_t index = 0; index < component_name.size(); index++)
1009 log::error(
"[checkJointLimit] Goal value exceeded limit at " +
STRING(component_name.at(index)) +
".");
1018 for(uint32_t index = 0; index < component_name.size(); index++)
1022 log::error(
"[checkJointLimit] Goal value exceeded limit at " +
STRING(component_name.at(index)) +
".");
1040 if(present_joint_value.size() != 0)
1047 std::vector<double> goal_joint_position;
1049 goal_joint_position.push_back(present_way_point.at(i).position + delta_goal_joint_position.at(i));
1059 if(present_joint_value.size() != 0)
1071 goal_way_point_temp.
position = goal_joint_position.at(index);
1072 goal_way_point_temp.
velocity = 0.0;
1074 goal_way_point_temp.
effort = 0.0;
1076 goal_way_point.push_back(goal_way_point_temp);
1096 if(present_joint_value.size() != 0)
1118 if(present_joint_value.size() != 0)
1126 goal_pose.
position = goal_position;
1133 if(present_joint_value.size() != 0)
1148 if(present_joint_value.size() != 0)
1159 Pose temp_goal_pose;
1162 std::vector<JointValue> goal_joint_angle;
1177 log::error(
"[JOINT_TRAJECTORY] Fail to solve IK");
1184 if(present_joint_value.size() != 0)
1199 if(present_joint_value.size() != 0)
1214 if(present_joint_value.size() != 0)
1229 if(present_joint_value.size() != 0)
1237 goal_pose.
position = goal_position;
1244 if(present_joint_value.size() != 0)
1263 if(present_joint_value.size() != 0)
1272 goal_task_way_point.
kinematic = goal_pose;
1275 Pose temp_goal_pose;
1278 std::vector<JointValue> goal_joint_angle;
1294 log::error(
"[TASK_TRAJECTORY] Fail to solve IK");
1310 if(present_joint_value.size() != 0)
1334 if(present_joint_value.size() != 0)
1358 if(present_joint_value.size() != 0)
1382 tool_value.
position = tool_goal_position;
1438 log::error(
"[TASK_TRAJECTORY] fail to solve IK");
1484 log::error(
"[CUSTOM_TASK_TRAJECTORY] fail to solve IK");
1496 std::map<Name, double> joint_torque_map;
1502 std::vector<double> joint_torque;
1503 for(uint8_t i = 0; i < names.size(); i++)
1505 if(joint_torque_map.find(names.at(i))!=joint_torque_map.end())
1506 joint_torque.push_back(joint_torque_map.at(names.at(i)));
1508 joint_torque.push_back(0.0);
1514 log::error(
"[getTrajectoryJointValue] fail to add goal effort.");
1527 std::vector<double> joint_torque;
1528 for(uint8_t i = 0; i < names.size(); i++)
1530 if(joint_torque_map.find(names.at(i))!=joint_torque_map.end())
1531 joint_torque.push_back(joint_torque_map.at(names.at(i)));
1533 joint_torque.push_back(0.0);
1550 return joint_way_point_value;
1583 return joint_goal_way_point;
1614 return joint_goal_way_point;
1633 std::vector<JointValue> result_vector;
1635 for(uint32_t index =0; index<tool_component_name.size(); index++)
1639 return result_vector;
bool checkJointLimit(Name component_name, double position)
void disableActuator(Name actuator_name)
void setComponentActuatorName(Name component_name, Name actuator_name)
bool makeJointTrajectory(JointWaypoint start_way_point, JointWaypoint goal_way_point)
makeJointTrajectory
Name getPresentCustomTrajectoryName()
JointActuator * getJointActuator(Name actuator_name)
void addTool(Name my_name, Name parent_name, Eigen::Vector3d relative_position, Eigen::Matrix3d relative_orientation, int8_t tool_id=-1, double max_position_limit=M_PI, double min_position_limit=-M_PI, double coefficient=1.0, double object_mass=0.0, Eigen::Matrix3d object_inertia_tensor=Eigen::Matrix3d::Identity(), Eigen::Vector3d object_center_of_mass=Eigen::Vector3d::Zero())
std::vector< JointValue > getToolGoalValue()
getToolGoalValue
bool sleepTrajectory(double wait_time, std::vector< JointValue > present_joint_value={})
sleepTrajectory
std::vector< Name > getAllToolComponentName()
void disableAllJointActuator()
std::vector< JointValue > receiveAllToolActuatorValue()
std::vector< JointValue > getJointGoalValueFromTrajectoryTickTime(double tick_time)
void setPresentJointWaypoint(JointWaypoint joint_value_vector)
Name findComponentNameUsingId(int8_t id)
bool kinematics_added_state_
std::vector< JointValue > getAllJointValue()
bool setToolGoalValue(Name tool_name, JointValue tool_goal_value)
setToolGoalValue
std::map< Name, Component >::iterator getIteratorEnd()
std::vector< JointValue > getJointGoalValueFromTrajectory(double present_time, int option=DYNAMICS_ALL_SOVING)
getJointGoalValueFromTrajectory
Pose getComponentPoseFromWorld(Name component_name)
CustomTaskTrajectory * getCustomTaskTrajectory(Name name)
void addWorld(Name world_name, Name child_name, Eigen::Vector3d world_position=Eigen::Vector3d::Zero(), Eigen::Matrix3d world_orientation=Eigen::Matrix3d::Identity())
void setStartTimeToPresentTime()
Kinematics * getKinematics()
JointValue getJointValue(Name component_name)
virtual void solveForwardKinematics(Manipulator *manipulator)=0
bool makeTaskTrajectoryFromPresentPose(Name tool_name, Eigen::Vector3d position_meter, double move_time, std::vector< JointValue > present_joint_value={})
makeTaskTrajectoryFromPresentPose
void setPresentControlToolName(Name present_control_tool_name)
virtual bool solveInverseKinematics(Manipulator *manipulator, Name tool_name, Pose target_pose, std::vector< JointValue > *goal_joint_position)=0
void addCustomTrajectory(Name trajectory_name, CustomJointTrajectory *custom_trajectory)
void initTrajectoryWaypoint(Manipulator actual_manipulator, Kinematics *kinematics=nullptr)
Eigen::Matrix3d getComponentOrientationFromWorld(Name component_name)
void setTorqueCoefficient(Name component_name, double torque_coefficient)
bool checkComponentType(Name component_name, ComponentType component_type)
bool checkTrajectoryType(TrajectoryType trajectory_type)
TaskTrajectory getTaskTrajectory()
std::vector< JointValue > getAllActiveJointValue()
bool makeTaskTrajectory(Name tool_name, Eigen::Vector3d goal_position, double move_time, std::vector< JointValue > present_joint_value={})
makeTaskTrajectory
JointWaypoint getTrajectoryJointValue(double tick_time, int option=0)
bool makeCustomTrajectory(Name trajectory_name, Name tool_name, const void *arg, double move_time, std::vector< JointValue > present_joint_value={})
makeCustomTrajectory
bool getActuatorEnabledState(Name actuator_name)
virtual Eigen::MatrixXd jacobian(Manipulator *manipulator, Name tool_name)=0
bool setEffortToValue(std::vector< JointValue > *value, std::vector< double > effort)
DynamicPose getDynamicPose(Name component_name)
void enableAllJointActuator()
bool tool_actuator_added_stete_
bool makeJointTrajectory(std::vector< double > goal_joint_position, double move_time, std::vector< JointValue > present_joint_value={})
makeJointTrajectory
bool solveGravityTerm(std::map< Name, double > *joint_torque)
KinematicPose getKinematicPose(Name component_name)
void printManipulatorSetting()
void setPresentTaskWaypoint(Name tool_name, TaskWaypoint tool_position_value_vector)
void enableActuator(Name actuator_name)
bool sendJointActuatorValue(Name joint_component_name, JointValue value)
bool getMovingFailState()
void addJoint(Name my_name, Name parent_name, Name child_name, Eigen::Vector3d relative_position, Eigen::Matrix3d relative_orientation, Eigen::Vector3d axis_of_rotation=Eigen::Vector3d::Zero(), int8_t joint_actuator_id=-1, double max_position_limit=M_PI, double min_position_limit=-M_PI, double coefficient=1.0, double mass=0.0, Eigen::Matrix3d inertia_tensor=Eigen::Matrix3d::Identity(), Eigen::Vector3d center_of_mass=Eigen::Vector3d::Zero(), double torque_coefficient=1.0)
void setKinematicsOption(const void *arg)
virtual ~RobotisManipulator()
bool checkJointLimit(Name Component_name, double value)
virtual bool setOption(STRING param_name, const void *arg)=0
void setTrajectoryType(TrajectoryType trajectory_type)
JointValue getToolGoalValue(Name tool_name)
CustomJointTrajectory * getCustomJointTrajectory(Name name)
std::vector< JointValue > JointWaypoint
std::vector< JointValue > getAllJointValue()
bool makeCustomTrajectory(Name trajectory_name, JointWaypoint start_way_point, const void *arg)
makeCustomTrajectory
std::vector< JointValue > receiveMultipleJointActuatorValue(std::vector< Name > joint_component_name)
void updatePresentWaypoint(Kinematics *kinematics)
Name getPresentControlToolName()
Name getComponentActuatorName(Name component_name)
void setAllActiveJointValue(std::vector< JointValue > joint_value_vector)
uint8_t getToolActuatorId(Name actuator_name)
std::vector< Name > getAllActiveJointComponentName()
void addComponentChild(Name my_name, Name child_name)
bool makeJointTrajectoryFromPresentPosition(std::vector< double > delta_goal_joint_position, double move_time, std::vector< JointValue > present_joint_value={})
makeJointTrajectoryFromPresentPosition
std::vector< JointValue > receiveAllJointActuatorValue()
void setMoveTime(double move_time)
Manipulator * getManipulator()
void setToolActuatorMode(Name actuator_name, const void *arg)
void setPresentTime(double present_time)
bool dynamics_added_state_
double getCoefficient(Name component_name)
JointValue getJointValue(Name joint_name)
std::vector< JointValue > getAllActiveJointValue()
virtual bool solveForwardDynamics(Manipulator *manipulator, std::map< Name, double > joint_torque)=0
double getTrajectoryMoveTime()
void setDynamicsEnvironments(STRING param_name, const void *arg)
JointWaypoint getPresentJointWaypoint()
bool makeToolTrajectory(Name tool_name, double tool_goal_position)
makeToolTrajectory
ToolActuator * getToolActuator(Name actuator_name)
void addDynamics(Dynamics *dynamics)
DynamicPose getComponentDynamicPoseFromWorld(Name component_name)
void solveForwardKinematics()
JointWaypoint getJointWaypoint(double tick)
Pose getPose(Name component_name)
void printManipulatorSetting()
virtual void setOption(const void *arg)=0
bool trajectory_initialized_state_
double getTorqueCoefficient(Name component_name)
Manipulator * getManipulator()
#define DYNAMICS_ALL_SOVING
bool solveInverseDynamics(std::map< Name, double > *joint_torque)
void setTorqueCoefficient(Name component_name, double torque_coefficient)
Trajectory * getTrajectory()
void resetMovingFailState()
void disableAllActuator()
std::vector< uint8_t > getJointActuatorId(Name actuator_name)
JointValue receiveJointActuatorValue(Name joint_component_name)
virtual bool solveInverseDynamics(Manipulator manipulator, std::map< Name, double > *joint_torque)=0
bool sendAllToolActuatorValue(std::vector< JointValue > value_vector)
bool makeTaskTrajectory(TaskWaypoint start_way_point, TaskWaypoint goal_way_point)
makeTaskTrajectory
bool sendMultipleJointActuatorValue(std::vector< Name > joint_component_name, std::vector< JointValue > value_vector)
TaskWaypoint getTaskWaypoint(double tick)
bool sendAllJointActuatorValue(std::vector< JointValue > value_vector)
std::vector< JointValue > receiveMultipleToolActuatorValue(std::vector< Name > tool_component_name)
Eigen::MatrixXd jacobian(Name tool_name)
JointTrajectory getJointTrajectory()
virtual bool setEnvironments(STRING param_name, const void *arg)=0
void addJoint(Name my_name, Name parent_name, Name child_name, Eigen::Vector3d relative_position, Eigen::Matrix3d relative_orientation, Eigen::Vector3d axis_of_rotation=Eigen::Vector3d::Zero(), int8_t joint_actuator_id=-1, double max_position_limit=M_PI, double min_position_limit=-M_PI, double coefficient=1.0, double mass=0.0, Eigen::Matrix3d inertia_tensor=Eigen::Matrix3d::Identity(), Eigen::Vector3d center_of_mass=Eigen::Vector3d::Zero(), double torque_coefficient=1.0)
std::vector< JointValue > getAllToolValue()
void setJointValue(Name name, JointValue joint_value)
void setCustomTrajectoryOption(Name trajectory_name, const void *arg)
setCustomTrajectoryOption
std::map< Name, ToolActuator * > tool_actuator_
bool solveInverseKinematics(Name tool_name, Pose goal_pose, std::vector< JointValue > *goal_joint_value)
JointValue getToolValue(Name tool_name)
bool sendMultipleToolActuatorValue(std::vector< Name > tool_component_name, std::vector< JointValue > value_vector)
Eigen::Vector3d getComponentPositionFromWorld(Name component_name)
void addComponentChild(Name my_name, Name child_name)
void enableAllToolActuator()
JointWaypoint removeWaypointDynamicData(JointWaypoint value)
void solveForwardDynamics(std::map< Name, double > joint_torque)
KinematicPose getComponentKinematicPoseFromWorld(Name component_name)
void setAllToolValue(std::vector< JointValue > tool_value_vector)
std::map< Name, Component >::iterator getIteratorBegin()
void addCustomTrajectory(Name trajectory_name, CustomJointTrajectory *custom_trajectory)
bool sendToolActuatorValue(Name tool_component_name, JointValue value)
TaskWaypoint getPresentTaskWaypoint(Name tool_name)
bool joint_actuator_added_stete_
#define DYNAMICS_GRAVITY_ONLY
void addKinematics(Kinematics *kinematics)
JointValue receiveToolActuatorValue(Name tool_component_name)
void setDynamicsOption(STRING param_name, const void *arg)
Eigen::Matrix3d orientation
std::vector< double > getAllToolPosition()
std::map< Name, JointActuator * > joint_actuator_
void addJointActuator(Name actuator_name, JointActuator *joint_actuator, std::vector< uint8_t > id_array, const void *arg)
void setJointActuatorMode(Name actuator_name, std::vector< uint8_t > id_array, const void *arg)
void setCustomTrajectoryOption(Name trajectory_name, const void *arg)
void disableAllToolActuator()
std::vector< double > getAllToolPosition()
int8_t getId(Name component_name)
std::vector< JointValue > getAllToolValue()
void addTool(Name my_name, Name parent_name, Eigen::Vector3d relative_position, Eigen::Matrix3d relative_orientation, int8_t tool_id=-1, double max_position_limit=M_PI, double min_position_limit=-M_PI, double coefficient=1.0, double mass=0.0, Eigen::Matrix3d inertia_tensor=Eigen::Matrix3d::Identity(), Eigen::Vector3d center_of_mass=Eigen::Vector3d::Zero(), double torque_coefficient=1.0)
void addWorld(Name world_name, Name child_name, Eigen::Vector3d world_position=Eigen::Vector3d::Zero(), Eigen::Matrix3d world_orientation=Eigen::Matrix3d::Identity())
void addToolActuator(Name tool_name, ToolActuator *tool_actuator, uint8_t id, const void *arg)